From 873e091eae55ae9c363ae4e79c1b6905f579c4f1 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 20 Jun 2016 11:31:45 -0700 Subject: [PATCH 001/155] build: switched to MttrCubeBlack for travis testing --- .travis.yml | 43 +++++++++++----------------------- Tools/scripts/mttr-build-ci.sh | 24 +++++++++++++++++++ 2 files changed, 38 insertions(+), 29 deletions(-) create mode 100755 Tools/scripts/mttr-build-ci.sh diff --git a/.travis.yml b/.travis.yml index eb1d9e0b72..34bc45c9f5 100644 --- a/.travis.yml +++ b/.travis.yml @@ -32,10 +32,9 @@ cache: before_install: - echo 0 | sudo dd of=/proc/sys/kernel/yama/ptrace_scope - Tools/scripts/configure-ci.sh - - if [ "$TRAVIS_EVENT_TYPE" = "cron" ]; then export CI_CRON_JOB=1 ; fi script: - - Tools/scripts/build_ci.sh + - Tools/scripts/mttr-build-ci.sh notifications: webhooks: @@ -45,6 +44,9 @@ notifications: on_failure: always # options: [always|never|change] default: always on_start: false # default: false +before_cache: + - ccache -z + compiler: - gcc @@ -58,30 +60,13 @@ env: matrix: fast_finish: true include: - - if: type != cron - compiler: "gcc" - env: CI_BUILD_TARGET="revo-bootloader periph-build CubeOrange-bootloader iofirmware stm32f7 stm32h7 fmuv2-plane" - - if: type != cron - compiler: "gcc" - env: CI_BUILD_TARGET="sitltest-copter" - - if: type != cron - compiler: "gcc" - env: CI_BUILD_TARGET="sitltest-quadplane sitltest-plane" - - if: type != cron - compiler: "clang-7" - env: CI_BUILD_TARGET="sitltest-rover sitltest-sub sitltest-balancebot" - - if: type != cron - compiler: "gcc" - env: CI_BUILD_TARGET="unit-tests" - - if: type != cron - compiler: "clang-7" - env: CI_BUILD_TARGET="sitl" - - language: python - python: 3.7 - addons: # speedup: This test does not need addons - compiler: - dist: xenial # required for Python >= 3.7 (travis-ci/travis-ci#9069) - before_install: pip install flake8 - script: - - EXCLUDE=./.*,./modules/gtest,./modules/ChibiOS/test,./modules/uavcan/libuavcan,./modules/libcanard - - flake8 . --count --exclude=$EXCLUDE --select=E901,E999,F821,F822,F823 --show-source --statistics + - compiler: "gcc" + +deploy: + provider: releases + api_key: "$GITHUB_DEPLOY_API_KEY" + file_glob: true + file: "$HOME/deploy_files/*" + on: + tags: true +>>>>>>> build: switched to MttrCubeBlack for travis testing diff --git a/Tools/scripts/mttr-build-ci.sh b/Tools/scripts/mttr-build-ci.sh new file mode 100755 index 0000000000..bda062f96c --- /dev/null +++ b/Tools/scripts/mttr-build-ci.sh @@ -0,0 +1,24 @@ +#!/bin/bash + +set -ex + +. ~/.profile + +mkdir -p "$HOME/deploy_files" + +python Tools/autotest/param_metadata/param_parse.py --vehicle ArduCopter +mv apm.pdef.xml "$HOME/deploy_files" + +# export PX4_PX4IO_NAME="px4io-v2" + +unset CXX CC + +./waf distclean +./waf configure --board=MttrCubeBlack +./waf build --targets bin/arducopter -j8 +./waf configure --board=sitl +./waf build --targets bin/arducopter -j8 + +mv build/MttrCubeBlack/bin/arducopter.apj "$HOME/deploy_files" +mv build/MttrCubeBlack/bin/arducopter "$HOME/deploy_files/fmu.elf" +mv build/sitl/bin/arducopter "$HOME/deploy_files/sitl.elf" From 5dba242b0d1d0d0713252dec03e27ebc35a0693c Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 24 Jun 2016 15:39:26 -0700 Subject: [PATCH 002/155] AC_PrecLand: add send_landing_target --- libraries/AC_PrecLand/AC_PrecLand.cpp | 21 +++++++++++++++++++++ libraries/AC_PrecLand/AC_PrecLand.h | 6 ++++++ 2 files changed, 27 insertions(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 701c94aac9..0526e9170b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -250,6 +250,16 @@ bool AC_PrecLand::get_target_velocity_relative_cms(Vector2f& ret) return true; } +bool AC_PrecLand::get_target_position_relative_measured_cm(Vector2f& ret) +{ + if (!target_acquired()) { + return false; + } + ret.x = _target_pos_rel_meas_NED.x*100.0f; + ret.y = _target_pos_rel_meas_NED.y*100.0f; + return true; +} + // handle_msg - Process a LANDING_TARGET mavlink message void AC_PrecLand::handle_msg(const mavlink_message_t &msg) { @@ -448,3 +458,14 @@ void AC_PrecLand::run_output_prediction() _target_pos_rel_out_NE.x += land_ofs_ned_m.x; _target_pos_rel_out_NE.y += land_ofs_ned_m.y; } + +// send landing target mavlink message to ground station +void AC_PrecLand::send_landing_target(mavlink_channel_t chan) +{ + mavlink_msg_landing_target_send(chan, + _last_update_ms, + target_acquired(), + MAV_FRAME_GLOBAL_TERRAIN_ALT, + _ekf_x.getPos()*100.0f, _ekf_y.getPos()*100.0f, 0.0f, 0.0f, 0.0f); + +} diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 1253530966..dd04c71805 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -79,6 +79,9 @@ class AC_PrecLand // returns target position relative to vehicle bool get_target_position_relative_cm(Vector2f& ret); + // get measured position of target if available + bool get_target_position_relative_measured_cm(Vector2f& ret); + // returns target velocity relative to vehicle bool get_target_velocity_relative_cms(Vector2f& ret); @@ -88,6 +91,9 @@ class AC_PrecLand // process a LANDING_TARGET mavlink message void handle_msg(const mavlink_message_t &msg); + // send GCS_MAVLink message + void send_landing_target(mavlink_channel_t chan); + // parameter var table static const struct AP_Param::GroupInfo var_info[]; From b9af39a49890f81c6616b8af388b18f45a88b496 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 27 Jul 2017 10:49:47 -0700 Subject: [PATCH 003/155] AC_PrecLand: add acceleration bias learning --- libraries/AC_PrecLand/PosVelEKF.cpp | 104 ++++++++++++++++------------ libraries/AC_PrecLand/PosVelEKF.h | 14 ++-- 2 files changed, 70 insertions(+), 48 deletions(-) diff --git a/libraries/AC_PrecLand/PosVelEKF.cpp b/libraries/AC_PrecLand/PosVelEKF.cpp index 935a3d4ba1..410c670912 100644 --- a/libraries/AC_PrecLand/PosVelEKF.cpp +++ b/libraries/AC_PrecLand/PosVelEKF.cpp @@ -7,87 +7,103 @@ __RET_NIS = ((-__X[0] + __Z)*(-__X[0] + __Z))/(__P[0] + __R); #define POSVELEKF_POS_CALC_STATE(__P, __R, __X, __Z, __RET_STATE) \ __RET_STATE[0] = __P[0]*(-__X[0] + __Z)/(__P[0] + __R) + __X[0]; __RET_STATE[1] = __P[1]*(-__X[0] + \ -__Z)/(__P[0] + __R) + __X[1]; +__Z)/(__P[0] + __R) + __X[1]; __RET_STATE[2] = __P[2]*(-__X[0] + __Z)/(__P[0] + __R) + __X[2]; #define POSVELEKF_POS_CALC_COV(__P, __R, __X, __Z, __RET_COV) \ __RET_COV[0] = ((__P[0])*(__P[0]))*__R/((__P[0] + __R)*(__P[0] + __R)) + __P[0]*((-__P[0]/(__P[0] + \ __R) + 1)*(-__P[0]/(__P[0] + __R) + 1)); __RET_COV[1] = __P[0]*__P[1]*__R/((__P[0] + __R)*(__P[0] + \ __R)) - __P[0]*__P[1]*(-__P[0]/(__P[0] + __R) + 1)/(__P[0] + __R) + __P[1]*(-__P[0]/(__P[0] + __R) + \ -1); __RET_COV[2] = ((__P[1])*(__P[1]))*__R/((__P[0] + __R)*(__P[0] + __R)) - \ -((__P[1])*(__P[1]))/(__P[0] + __R) - __P[1]*(-__P[0]*__P[1]/(__P[0] + __R) + __P[1])/(__P[0] + __R) + \ -__P[2]; - -#define POSVELEKF_PREDICTION_CALC_STATE(__P, __DT, __DV, __DV_NOISE, __X, __RET_STATE) \ -__RET_STATE[0] = __DT*__X[1] + __X[0]; __RET_STATE[1] = __DV + __X[1]; - -#define POSVELEKF_PREDICTION_CALC_COV(__P, __DT, __DV, __DV_NOISE, __X, __RET_COV) \ -__RET_COV[0] = __DT*__P[1] + __DT*(__DT*__P[2] + __P[1]) + __P[0]; __RET_COV[1] = __DT*__P[2] + \ -__P[1]; __RET_COV[2] = ((__DV_NOISE)*(__DV_NOISE)) + __P[2]; +1); __RET_COV[2] = __P[0]*__P[2]*__R/((__P[0] + __R)*(__P[0] + __R)) - __P[0]*__P[2]*(-__P[0]/(__P[0] \ ++ __R) + 1)/(__P[0] + __R) + __P[2]*(-__P[0]/(__P[0] + __R) + 1); __RET_COV[3] = \ +((__P[1])*(__P[1]))*__R/((__P[0] + __R)*(__P[0] + __R)) - ((__P[1])*(__P[1]))/(__P[0] + __R) - \ +__P[1]*(-__P[0]*__P[1]/(__P[0] + __R) + __P[1])/(__P[0] + __R) + __P[3]; __RET_COV[4] = \ +__P[1]*__P[2]*__R/((__P[0] + __R)*(__P[0] + __R)) - __P[1]*__P[2]/(__P[0] + __R) - \ +__P[2]*(-__P[0]*__P[1]/(__P[0] + __R) + __P[1])/(__P[0] + __R) + __P[4]; __RET_COV[5] = \ +((__P[2])*(__P[2]))*__R/((__P[0] + __R)*(__P[0] + __R)) - ((__P[2])*(__P[2]))/(__P[0] + __R) - \ +__P[2]*(-__P[0]*__P[2]/(__P[0] + __R) + __P[2])/(__P[0] + __R) + __P[5]; + +#define POSVELEKF_PREDICTION_CALC_STATE(__P, __ABIAS_PNOISE, __DT, __DV, __DV_NOISE, __X, __RET_STATE) \ +__RET_STATE[0] = __DT*__X[1] + __X[0]; __RET_STATE[1] = -__DT*__X[2] + __DV + __X[1]; __RET_STATE[2] \ += __X[2]; + +#define POSVELEKF_PREDICTION_CALC_COV(__P, __ABIAS_PNOISE, __DT, __DV, __DV_NOISE, __X, __RET_COV) \ +__RET_COV[0] = __DT*__P[1] + __DT*(__DT*__P[3] + __P[1]) + __P[0]; __RET_COV[1] = __DT*__P[3] - \ +__DT*(__DT*__P[4] + __P[2]) + __P[1]; __RET_COV[2] = __DT*__P[4] + __P[2]; __RET_COV[3] = \ +-__DT*__P[4] - __DT*(-__DT*__P[5] + __P[4]) + ((__DV_NOISE)*(__DV_NOISE)) + __P[3]; __RET_COV[4] = \ +-__DT*__P[5] + __P[4]; __RET_COV[5] = ((__ABIAS_PNOISE)*(__ABIAS_PNOISE))*((__DT)*(__DT)) + __P[5]; #define POSVELEKF_VEL_CALC_NIS(__P, __R, __X, __Z, __RET_NIS) \ -__RET_NIS = ((-__X[1] + __Z)*(-__X[1] + __Z))/(__P[2] + __R); +__RET_NIS = ((-__X[1] + __Z)*(-__X[1] + __Z))/(__P[3] + __R); #define POSVELEKF_VEL_CALC_STATE(__P, __R, __X, __Z, __RET_STATE) \ -__RET_STATE[0] = __P[1]*(-__X[1] + __Z)/(__P[2] + __R) + __X[0]; __RET_STATE[1] = __P[2]*(-__X[1] + \ -__Z)/(__P[2] + __R) + __X[1]; +__RET_STATE[0] = __P[1]*(-__X[1] + __Z)/(__P[3] + __R) + __X[0]; __RET_STATE[1] = __P[3]*(-__X[1] + \ +__Z)/(__P[3] + __R) + __X[1]; __RET_STATE[2] = __P[4]*(-__X[1] + __Z)/(__P[3] + __R) + __X[2]; #define POSVELEKF_VEL_CALC_COV(__P, __R, __X, __Z, __RET_COV) \ -__RET_COV[0] = __P[0] + ((__P[1])*(__P[1]))*__R/((__P[2] + __R)*(__P[2] + __R)) - \ -((__P[1])*(__P[1]))/(__P[2] + __R) - __P[1]*(-__P[1]*__P[2]/(__P[2] + __R) + __P[1])/(__P[2] + __R); \ -__RET_COV[1] = __P[1]*__P[2]*__R/((__P[2] + __R)*(__P[2] + __R)) + (-__P[2]/(__P[2] + __R) + \ -1)*(-__P[1]*__P[2]/(__P[2] + __R) + __P[1]); __RET_COV[2] = ((__P[2])*(__P[2]))*__R/((__P[2] + \ -__R)*(__P[2] + __R)) + __P[2]*((-__P[2]/(__P[2] + __R) + 1)*(-__P[2]/(__P[2] + __R) + 1)); +__RET_COV[0] = __P[0] + ((__P[1])*(__P[1]))*__R/((__P[3] + __R)*(__P[3] + __R)) - \ +((__P[1])*(__P[1]))/(__P[3] + __R) - __P[1]*(-__P[1]*__P[3]/(__P[3] + __R) + __P[1])/(__P[3] + __R); \ +__RET_COV[1] = __P[1]*__P[3]*__R/((__P[3] + __R)*(__P[3] + __R)) + (-__P[3]/(__P[3] + __R) + \ +1)*(-__P[1]*__P[3]/(__P[3] + __R) + __P[1]); __RET_COV[2] = __P[1]*__P[4]*__R/((__P[3] + __R)*(__P[3] \ ++ __R)) - __P[1]*__P[4]/(__P[3] + __R) + __P[2] - __P[4]*(-__P[1]*__P[3]/(__P[3] + __R) + \ +__P[1])/(__P[3] + __R); __RET_COV[3] = ((__P[3])*(__P[3]))*__R/((__P[3] + __R)*(__P[3] + __R)) + \ +__P[3]*((-__P[3]/(__P[3] + __R) + 1)*(-__P[3]/(__P[3] + __R) + 1)); __RET_COV[4] = \ +__P[3]*__P[4]*__R/((__P[3] + __R)*(__P[3] + __R)) - __P[3]*__P[4]*(-__P[3]/(__P[3] + __R) + \ +1)/(__P[3] + __R) + __P[4]*(-__P[3]/(__P[3] + __R) + 1); __RET_COV[5] = \ +((__P[4])*(__P[4]))*__R/((__P[3] + __R)*(__P[3] + __R)) - ((__P[4])*(__P[4]))/(__P[3] + __R) - \ +__P[4]*(-__P[3]*__P[4]/(__P[3] + __R) + __P[4])/(__P[3] + __R) + __P[5]; void PosVelEKF::init(float pos, float posVar, float vel, float velVar) { - _state[0] = pos; - _state[1] = vel; - _cov[0] = posVar; - _cov[1] = 0.0f; - _cov[2] = velVar; + uint8_t next_state_idx = (_state_idx+1)%2; + + _state[next_state_idx].x[0] = pos; + _state[next_state_idx].x[1] = vel; + _state[next_state_idx].x[2] = 0; + _state[next_state_idx].P[0] = posVar; + _state[next_state_idx].P[1] = 0.0f; + _state[next_state_idx].P[2] = 0.0f; + _state[next_state_idx].P[3] = velVar; + _state[next_state_idx].P[4] = 0.0f; + _state[next_state_idx].P[5] = 0.05f*0.05f; + + _state_idx = next_state_idx; } void PosVelEKF::predict(float dt, float dVel, float dVelNoise) { - float newState[2]; - float newCov[3]; - - POSVELEKF_PREDICTION_CALC_STATE(_cov, dt, dVel, dVelNoise, _state, newState) - POSVELEKF_PREDICTION_CALC_COV(_cov, dt, dVel, dVelNoise, _state, newCov) + uint8_t next_state_idx = (_state_idx+1)%2; + const float abias_pnoise = 0.005f; + POSVELEKF_PREDICTION_CALC_STATE(_state[_state_idx].P, abias_pnoise, dt, dVel, dVelNoise, _state[_state_idx].x, _state[next_state_idx].x) + POSVELEKF_PREDICTION_CALC_COV(_state[_state_idx].P, abias_pnoise, dt, dVel, dVelNoise, _state[_state_idx].x, _state[next_state_idx].P) - memcpy(_state,newState,sizeof(_state)); - memcpy(_cov,newCov,sizeof(_cov)); + _state_idx = next_state_idx; } void PosVelEKF::fusePos(float pos, float posVar) { - float newState[2]; - float newCov[3]; + uint8_t next_state_idx = (_state_idx+1)%2; - POSVELEKF_POS_CALC_STATE(_cov, posVar, _state, pos, newState) - POSVELEKF_POS_CALC_COV(_cov, posVar, _state, pos, newCov) + POSVELEKF_POS_CALC_STATE(_state[_state_idx].P, posVar, _state[_state_idx].x, pos, _state[next_state_idx].x) + POSVELEKF_POS_CALC_COV(_state[_state_idx].P, posVar, _state[_state_idx].x, pos, _state[next_state_idx].P) - memcpy(_state,newState,sizeof(_state)); - memcpy(_cov,newCov,sizeof(_cov)); + _state_idx = next_state_idx; } void PosVelEKF::fuseVel(float vel, float velVar) { - float newState[2]; - float newCov[3]; + uint8_t next_state_idx = (_state_idx+1)%2; - POSVELEKF_VEL_CALC_STATE(_cov, velVar, _state, vel, newState) - POSVELEKF_VEL_CALC_COV(_cov, velVar, _state, vel, newCov) + POSVELEKF_VEL_CALC_STATE(_state[_state_idx].P, velVar, _state[_state_idx].x, vel, _state[next_state_idx].x) + POSVELEKF_VEL_CALC_COV(_state[_state_idx].P, velVar, _state[_state_idx].x, vel, _state[next_state_idx].P) - memcpy(_state,newState,sizeof(_state)); - memcpy(_cov,newCov,sizeof(_cov)); + _state_idx = next_state_idx; } float PosVelEKF::getPosNIS(float pos, float posVar) { float ret; - POSVELEKF_POS_CALC_NIS(_cov, posVar, _state, pos, ret) + POSVELEKF_POS_CALC_NIS(_state[_state_idx].P, posVar, _state[_state_idx].x, pos, ret) return ret; } diff --git a/libraries/AC_PrecLand/PosVelEKF.h b/libraries/AC_PrecLand/PosVelEKF.h index a769abd9e7..df7d72ab5c 100644 --- a/libraries/AC_PrecLand/PosVelEKF.h +++ b/libraries/AC_PrecLand/PosVelEKF.h @@ -1,5 +1,7 @@ #pragma once +#include + class PosVelEKF { public: void init(float pos, float posVar, float vel, float velVar); @@ -7,12 +9,16 @@ class PosVelEKF { void fusePos(float pos, float posVar); void fuseVel(float vel, float velVar); - float getPos() const { return _state[0]; } - float getVel() const { return _state[1]; } + float getPos() const { return _state[_state_idx].x[0]; } + float getVel() const { return _state[_state_idx].x[1]; } + float getABias() const { return _state[_state_idx].x[2]; } float getPosNIS(float pos, float posVar); private: - float _state[2]; - float _cov[3]; + struct { + float x[3]; + float P[6]; + } _state[2]; + uint8_t _state_idx; }; From fa921a0bed1acc8043ffcc0324acee97d6f807b1 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 1 Nov 2017 10:57:21 -0700 Subject: [PATCH 004/155] AC_PrecLand: account for vertical offset of camera when computing depth --- libraries/AC_PrecLand/AC_PrecLand.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 0526e9170b..5871ff6876 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -399,20 +399,21 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool alt_valid = (rangefinder_alt_valid && rangefinder_alt_m > 0.0f) || (_backend->distance_to_target() > 0.0f); if (target_vec_valid && alt_valid) { float dist, alt; + + Vector3f cam_pos_ned = inertial_data_delayed.Tbn * _cam_offset.get(); + if (_backend->distance_to_target() > 0.0f) { dist = _backend->distance_to_target(); alt = dist * target_vec_unit_ned.z; } else { - alt = MAX(rangefinder_alt_m, 0.0f); + alt = MAX(rangefinder_alt_m-cam_pos_ned.z, 0.0f); dist = alt / target_vec_unit_ned.z; } - // Compute camera position relative to IMU - Vector3f accel_body_offset = AP::ins().get_imu_pos_offset(AP::ahrs().get_primary_accel_index()); - Vector3f cam_pos_ned = inertial_data_delayed->Tbn * (_cam_offset.get() - accel_body_offset); - // Compute target position relative to IMU - _target_pos_rel_meas_NED = Vector3f(target_vec_unit_ned.x*dist, target_vec_unit_ned.y*dist, alt) + cam_pos_ned; + Vector3f imu_pos_ned = inertial_data_delayed.Tbn * AP::ins().get_ins().get_imu_pos_offset(_ahrs.get_primary_accel_index()); + Vector3f cam_pos_ned_rel_imu = cam_pos_ned-imu_pos_ned; + _target_pos_rel_meas_NED = Vector3f(target_vec_unit_ned.x*dist, target_vec_unit_ned.y*dist, alt) + cam_pos_ned_rel_imu; return true; } } From a5644134b75615b1d11ed07b8bc4257b06d69a8a Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 2 Feb 2018 12:33:50 -0800 Subject: [PATCH 005/155] AC_PrecLand: add get_height_above_target_cm --- libraries/AC_PrecLand/AC_PrecLand.cpp | 14 ++++++++++++++ libraries/AC_PrecLand/AC_PrecLand.h | 2 ++ 2 files changed, 16 insertions(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 5871ff6876..d75852a1b6 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -212,6 +212,20 @@ bool AC_PrecLand::target_acquired() return _target_acquired; } +bool AC_PrecLand::get_height_above_target_cm(int32_t& ret) { + if (!target_acquired()) { + return false; + } + + bool precland_uwb_range_valid = precland_uwb_range.valid && AP_HAL::millis()-precland_uwb_range.timestamp_ms < 100; + if (!precland_uwb_range_valid) { + return false; + } + + ret = precland_uwb_range.range * 100; + return true; +} + bool AC_PrecLand::get_target_position_cm(Vector2f& ret) { if (!target_acquired()) { diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index dd04c71805..790f91e84c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -85,6 +85,8 @@ class AC_PrecLand // returns target velocity relative to vehicle bool get_target_velocity_relative_cms(Vector2f& ret); + bool get_height_above_target_cm(int32_t& ret); + // returns true when the landing target has been detected bool target_acquired(); From 9a95350abe0396b2976012d05a315f7030e30966 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 6 Jun 2018 17:06:12 -0700 Subject: [PATCH 006/155] AC_PrecLand: add initialization period --- libraries/AC_PrecLand/AC_PrecLand.cpp | 20 +++++++++++++++++--- libraries/AC_PrecLand/AC_PrecLand.h | 2 ++ 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index d75852a1b6..a3d981a893 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -208,7 +208,11 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid) bool AC_PrecLand::target_acquired() { - _target_acquired = _target_acquired && (AP_HAL::millis()-_last_update_ms) < 2000; + if ((AP_HAL::millis()-_last_update_ms) >= 2000) { + _estimator_initialized = false; + _target_acquired = false; + } + return _target_acquired; } @@ -340,7 +344,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va // Update if a new Line-Of-Sight measurement is available if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) { float xy_pos_var = sq(_target_pos_rel_meas_NED.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f); - if (!target_acquired()) { + if (!_estimator_initialized) { // reset filter state if (inertial_data_delayed->inertialNavVelocityValid) { _ekf_x.init(_target_pos_rel_meas_NED.x, xy_pos_var, -inertial_data_delayed->inertialNavVelocity.x, sq(2.0f)); @@ -350,7 +354,8 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va _ekf_y.init(_target_pos_rel_meas_NED.y, xy_pos_var, 0.0f, sq(10.0f)); } _last_update_ms = AP_HAL::millis(); - _target_acquired = true; + _estimator_initialized = true; + _estimator_init_ms = AP_HAL::millis(); } else { float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_NED.x, xy_pos_var); float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_NED.y, xy_pos_var); @@ -366,6 +371,15 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va } } + // Check for estimator timeout + if (!target_acquired() && _estimator_initialized) { + if (AP_HAL::millis()-_last_update_ms > 200) { + _estimator_initialized = false; + } else if (AP_HAL::millis()-_estimator_init_ms > 2000) { + _target_acquired = true; + } + } + // Output prediction if (target_acquired()) { _target_pos_rel_est_NE.x = _ekf_x.getPos(); diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 790f91e84c..13d42d2db0 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -134,6 +134,8 @@ class AC_PrecLand AP_Vector3f _cam_offset; // Position of the camera relative to the CG uint32_t _last_update_ms; // system time in millisecond when update was last called + uint32_t _estimator_init_ms; + bool _estimator_initialized; bool _target_acquired; // true if target has been seen recently uint32_t _last_backend_los_meas_ms; // system time target was last seen From 10154c822350ebc04cdd562a3a23c6592200040c Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 27 Sep 2018 10:01:47 -1000 Subject: [PATCH 007/155] AC_PrecLand: fix bug in target acquired logic --- libraries/AC_PrecLand/AC_PrecLand.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index a3d981a893..2381f1847f 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -364,7 +364,6 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va _ekf_x.fusePos(_target_pos_rel_meas_NED.x, xy_pos_var); _ekf_y.fusePos(_target_pos_rel_meas_NED.y, xy_pos_var); _last_update_ms = AP_HAL::millis(); - _target_acquired = true; } else { _outlier_reject_count++; } From e69863c0e1c30ba5253e93dd5d86031622313e12 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 27 Sep 2018 10:06:39 -1000 Subject: [PATCH 008/155] AC_PrecLand: remove check that prevents rejection of more than 3 outliers in a row --- libraries/AC_PrecLand/AC_PrecLand.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 2381f1847f..9382c66310 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -359,8 +359,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va } else { float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_NED.x, xy_pos_var); float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_NED.y, xy_pos_var); - if (MAX(NIS_x, NIS_y) < 3.0f || _outlier_reject_count >= 3) { - _outlier_reject_count = 0; + if (MAX(NIS_x, NIS_y) < 3.0f) { _ekf_x.fusePos(_target_pos_rel_meas_NED.x, xy_pos_var); _ekf_y.fusePos(_target_pos_rel_meas_NED.y, xy_pos_var); _last_update_ms = AP_HAL::millis(); From 86ad55d9fb1c849ed00a6fde76f62174cb52eccd Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 27 Sep 2018 10:30:14 -1000 Subject: [PATCH 009/155] AC_PrecLand: add smoothing to output predictor --- libraries/AC_PrecLand/AC_PrecLand.cpp | 48 +++++++++++++++++---------- 1 file changed, 31 insertions(+), 17 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 9382c66310..56a255624e 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -356,6 +356,9 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va _last_update_ms = AP_HAL::millis(); _estimator_initialized = true; _estimator_init_ms = AP_HAL::millis(); + + _target_pos_rel_out_NE = Vector2f(_ekf_x.getPos(), _ekf_y.getPos()); + _target_vel_rel_out_NE = Vector2f(_ekf_x.getVel(), _ekf_y.getVel()); } else { float NIS_x = _ekf_x.getPosNIS(_target_pos_rel_meas_NED.x, xy_pos_var); float NIS_y = _ekf_y.getPosNIS(_target_pos_rel_meas_NED.y, xy_pos_var); @@ -379,7 +382,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va } // Output prediction - if (target_acquired()) { + if (_estimator_initialized) { _target_pos_rel_est_NE.x = _ekf_x.getPos(); _target_pos_rel_est_NE.y = _ekf_y.getPos(); _target_vel_rel_est_NE.x = _ekf_x.getVel(); @@ -448,16 +451,16 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, void AC_PrecLand::run_output_prediction() { - _target_pos_rel_out_NE = _target_pos_rel_est_NE; - _target_vel_rel_out_NE = _target_vel_rel_est_NE; + Vector2f target_pos_rel_est_corrected_NE = _target_pos_rel_est_NE; + Vector2f target_vel_rel_est_corrected_NE = _target_vel_rel_est_NE; // Predict forward from delayed time horizon - for (uint8_t i=1; i<_inertial_history->available(); i++) { - const struct inertial_data_frame_s *inertial_data = (*_inertial_history)[i]; - _target_vel_rel_out_NE.x -= inertial_data->correctedVehicleDeltaVelocityNED.x; - _target_vel_rel_out_NE.y -= inertial_data->correctedVehicleDeltaVelocityNED.y; - _target_pos_rel_out_NE.x += _target_vel_rel_out_NE.x * inertial_data->dt; - _target_pos_rel_out_NE.y += _target_vel_rel_out_NE.y * inertial_data->dt; + for (uint8_t i=1; i<_inertial_history.size(); i++) { + const struct inertial_data_frame_s& inertial_data = _inertial_history.peek(i); + target_vel_rel_est_corrected_NE.x -= inertial_data.correctedVehicleDeltaVelocityNED.x; + target_vel_rel_est_corrected_NE.y -= inertial_data.correctedVehicleDeltaVelocityNED.y; + target_pos_rel_est_corrected_NE.x += target_vel_rel_est_corrected_NE.x * inertial_data.dt; + target_pos_rel_est_corrected_NE.y += target_vel_rel_est_corrected_NE.y * inertial_data.dt; } const AP_AHRS &_ahrs = AP::ahrs(); @@ -467,23 +470,34 @@ void AC_PrecLand::run_output_prediction() // Apply position correction for CG offset from IMU Vector3f imu_pos_ned = Tbn * accel_body_offset; - _target_pos_rel_out_NE.x += imu_pos_ned.x; - _target_pos_rel_out_NE.y += imu_pos_ned.y; + target_pos_rel_est_corrected_NE.x += imu_pos_ned.x; + target_pos_rel_est_corrected_NE.y += imu_pos_ned.y; // Apply position correction for body-frame horizontal camera offset from CG, so that vehicle lands lens-to-target Vector3f cam_pos_horizontal_ned = Tbn * Vector3f(_cam_offset.get().x, _cam_offset.get().y, 0); - _target_pos_rel_out_NE.x -= cam_pos_horizontal_ned.x; - _target_pos_rel_out_NE.y -= cam_pos_horizontal_ned.y; + target_pos_rel_est_corrected_NE.x -= cam_pos_horizontal_ned.x; + target_pos_rel_est_corrected_NE.y -= cam_pos_horizontal_ned.y; // Apply velocity correction for IMU offset from CG Vector3f vel_ned_rel_imu = Tbn * (_ahrs.get_gyro() % (-accel_body_offset)); - _target_vel_rel_out_NE.x -= vel_ned_rel_imu.x; - _target_vel_rel_out_NE.y -= vel_ned_rel_imu.y; + target_vel_rel_est_corrected_NE.x -= vel_ned_rel_imu.x; + target_vel_rel_est_corrected_NE.y -= vel_ned_rel_imu.y; // Apply land offset Vector3f land_ofs_ned_m = _ahrs.get_rotation_body_to_ned() * Vector3f(_land_ofs_cm_x,_land_ofs_cm_y,0) * 0.01f; - _target_pos_rel_out_NE.x += land_ofs_ned_m.x; - _target_pos_rel_out_NE.y += land_ofs_ned_m.y; + target_pos_rel_est_corrected_NE.x += land_ofs_ned_m.x; + target_pos_rel_est_corrected_NE.y += land_ofs_ned_m.y; + + const struct inertial_data_frame_s& latest_inertial_data = _inertial_history.peek(_inertial_history.size()-1); + + _target_pos_rel_out_NE += _target_vel_rel_est_NE * latest_inertial_data.dt; + _target_vel_rel_out_NE += -Vector2f(latest_inertial_data.correctedVehicleDeltaVelocityNED.x, latest_inertial_data.correctedVehicleDeltaVelocityNED.y); + + const float tc = 0.3f; + float alpha = latest_inertial_data.dt/(latest_inertial_data.dt+tc); + + _target_pos_rel_out_NE += (target_pos_rel_est_corrected_NE - _target_pos_rel_out_NE) * alpha; + _target_vel_rel_out_NE += (target_vel_rel_est_corrected_NE - _target_vel_rel_out_NE) * alpha; } // send landing target mavlink message to ground station From 93ba3cec31194cd65c5cac5bb114dd7b93651208 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 30 Oct 2018 15:30:29 -0700 Subject: [PATCH 010/155] AC_PrecLand: increase pixycam measurement variance to 20 mrad --- libraries/AC_PrecLand/AC_PrecLand.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 56a255624e..2563c0e1f9 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -343,7 +343,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va // Update if a new Line-Of-Sight measurement is available if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) { - float xy_pos_var = sq(_target_pos_rel_meas_NED.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f); + float xy_pos_var = sq(_target_pos_rel_meas_NED.z*(0.02f + 0.02f*AP::ahrs().get_gyro().length()) + 0.02f); if (!_estimator_initialized) { // reset filter state if (inertial_data_delayed->inertialNavVelocityValid) { From 652223fca3c0feb3c359d76d20f754abbc173041 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 14 Nov 2018 15:37:41 -0800 Subject: [PATCH 011/155] AC_PrecLand: log raw los measurement --- libraries/AC_PrecLand/AC_PrecLand.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 2563c0e1f9..fa0965ab71 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -7,6 +7,7 @@ #include "AC_PrecLand_IRLock.h" #include "AC_PrecLand_SITL_Gazebo.h" #include "AC_PrecLand_SITL.h" +#include #include @@ -411,6 +412,8 @@ bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body) ); target_vec_unit_body = Rz*target_vec_unit_body; + + DataFlash_Class::instance()->Log_Write("LOSM", "TimeUS,LOSx,LOSy,LOSz", "Qfff", AP_HAL::micros64(), target_vec_unit_body.x, target_vec_unit_body.y, target_vec_unit_body.z); return true; } else { return false; From 6437575666663be3432f8938dfc0993dd53aa257 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Mar 2019 14:10:52 +1100 Subject: [PATCH 012/155] AC_PrecLand: rebase fixes --- libraries/AC_PrecLand/AC_PrecLand.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index fa0965ab71..77ff74082a 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -443,7 +443,7 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, } // Compute target position relative to IMU - Vector3f imu_pos_ned = inertial_data_delayed.Tbn * AP::ins().get_ins().get_imu_pos_offset(_ahrs.get_primary_accel_index()); + Vector3f imu_pos_ned = inertial_data_delayed.Tbn * AP::ins().get_imu_pos_offset(_ahrs.get_primary_accel_index()); Vector3f cam_pos_ned_rel_imu = cam_pos_ned-imu_pos_ned; _target_pos_rel_meas_NED = Vector3f(target_vec_unit_ned.x*dist, target_vec_unit_ned.y*dist, alt) + cam_pos_ned_rel_imu; return true; @@ -507,9 +507,10 @@ void AC_PrecLand::run_output_prediction() void AC_PrecLand::send_landing_target(mavlink_channel_t chan) { mavlink_msg_landing_target_send(chan, - _last_update_ms, - target_acquired(), - MAV_FRAME_GLOBAL_TERRAIN_ALT, - _ekf_x.getPos()*100.0f, _ekf_y.getPos()*100.0f, 0.0f, 0.0f, 0.0f); + _last_update_ms, + target_acquired(), + MAV_FRAME_GLOBAL_TERRAIN_ALT, + _ekf_x.getPos()*100.0f, _ekf_y.getPos()*100.0f, + 0.0f, 0.0f, 0.0f, 0, 0, 0, nullptr, 0, 0); } From e74ab22fff41a943ffe4a26cb63df729b9e1f3f1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Apr 2019 07:41:48 +1100 Subject: [PATCH 013/155] AC_PrecLand: added distance to target in SITL backend --- libraries/AC_PrecLand/AC_PrecLand_SITL.cpp | 10 ++++++++++ libraries/AC_PrecLand/AC_PrecLand_SITL.h | 4 ++++ 2 files changed, 14 insertions(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp index 52b806ea5e..f3ccaab691 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp @@ -18,6 +18,7 @@ void AC_PrecLand_SITL::update() if (_state.healthy && _sitl->precland_sim.last_update_ms() != _los_meas_time_ms) { const Vector3f position = _sitl->precland_sim.get_target_position(); const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned(); + _target_distance_m = position.length(); _los_meas_body = body_to_ned.mul_transpose(-position); _los_meas_body /= _los_meas_body.length(); _have_los_meas = true; @@ -45,4 +46,13 @@ bool AC_PrecLand_SITL::get_los_body(Vector3f& ret) { return true; } +// returns distance to target in meters (0 means distance is not known) +float AC_PrecLand_SITL::distance_to_target() +{ + if (AP_HAL::millis() - _los_meas_time_ms > 1000) { + return 0; + } + return _target_distance_m; +} + #endif diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.h b/libraries/AC_PrecLand/AC_PrecLand_SITL.h index 6821476a54..94e5257e79 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.h @@ -32,11 +32,15 @@ class AC_PrecLand_SITL : public AC_PrecLand_Backend // return true if there is a valid los measurement available bool have_los_meas() override; + // returns distance to target in meters (0 means distance is not known) + float distance_to_target() override; + private: SITL::SITL *_sitl; // sitl instance pointer Vector3f _los_meas_body; // unit vector in body frame pointing towards target uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured bool _have_los_meas; // true if there is a valid measurement from the camera + float _target_distance_m; }; #endif From dc46bfd3de9dcfc1afc070d48270eab20e96e512 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Apr 2019 09:11:28 +1100 Subject: [PATCH 014/155] AC_PrecLand: added debug for PL in SITL --- libraries/AC_PrecLand/AC_PrecLand.cpp | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 77ff74082a..f9c8f6d3b2 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -8,6 +8,7 @@ #include "AC_PrecLand_SITL_Gazebo.h" #include "AC_PrecLand_SITL.h" #include +#include #include @@ -323,6 +324,9 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va _target_vel_rel_est_NE.y = -inertial_data_delayed->inertialNavVelocity.y; _last_update_ms = AP_HAL::millis(); + if (!_target_acquired) { + gcs().send_text(MAV_SEVERITY_INFO, "PL: target acquired %.1m", rangefinder_alt_m); + } _target_acquired = true; } @@ -378,6 +382,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va if (AP_HAL::millis()-_last_update_ms > 200) { _estimator_initialized = false; } else if (AP_HAL::millis()-_estimator_init_ms > 2000) { + gcs().send_text(MAV_SEVERITY_INFO, "PL: target acquired2"); _target_acquired = true; } } @@ -391,6 +396,22 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va run_output_prediction(); } +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + { + static uint32_t last_print_ms; + uint32_t now = AP_HAL::millis(); + if (now - last_print_ms >= 1000) { + last_print_ms = now; + float dist = 0; + get_target_distance_m(dist); + printf("PL: TA:%u pos=(%.1f,%.1f) d=%.1f\n", + _target_acquired, + _target_pos_rel_est_NE.x, + _target_pos_rel_est_NE.y, + dist); + } + } +#endif break; } } From d227e4430ccd8412a452733acfe3dcaf585570a6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Apr 2019 09:33:19 +1100 Subject: [PATCH 015/155] AC_PrecLand: use internal quaternion for SITL precland --- libraries/AC_PrecLand/AC_PrecLand_SITL.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp index f3ccaab691..3ff6663d97 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.cpp @@ -17,7 +17,8 @@ void AC_PrecLand_SITL::update() if (_state.healthy && _sitl->precland_sim.last_update_ms() != _los_meas_time_ms) { const Vector3f position = _sitl->precland_sim.get_target_position(); - const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned(); + Matrix3f body_to_ned; + _sitl->state.quaternion.rotation_matrix(body_to_ned); _target_distance_m = position.length(); _los_meas_body = body_to_ned.mul_transpose(-position); _los_meas_body /= _los_meas_body.length(); From 881dab11db2e019face81a400834acd0a063ff57 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 17 Feb 2020 17:48:18 +1100 Subject: [PATCH 016/155] AC_PrecLand: rebase fixes --- libraries/AC_PrecLand/AC_PrecLand.cpp | 47 +++++---------------------- libraries/AC_PrecLand/AC_PrecLand.h | 2 -- 2 files changed, 9 insertions(+), 40 deletions(-) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index f9c8f6d3b2..ad51a5a597 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -7,7 +7,7 @@ #include "AC_PrecLand_IRLock.h" #include "AC_PrecLand_SITL_Gazebo.h" #include "AC_PrecLand_SITL.h" -#include +#include #include #include @@ -218,20 +218,6 @@ bool AC_PrecLand::target_acquired() return _target_acquired; } -bool AC_PrecLand::get_height_above_target_cm(int32_t& ret) { - if (!target_acquired()) { - return false; - } - - bool precland_uwb_range_valid = precland_uwb_range.valid && AP_HAL::millis()-precland_uwb_range.timestamp_ms < 100; - if (!precland_uwb_range_valid) { - return false; - } - - ret = precland_uwb_range.range * 100; - return true; -} - bool AC_PrecLand::get_target_position_cm(Vector2f& ret) { if (!target_acquired()) { @@ -325,7 +311,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va _last_update_ms = AP_HAL::millis(); if (!_target_acquired) { - gcs().send_text(MAV_SEVERITY_INFO, "PL: target acquired %.1m", rangefinder_alt_m); + gcs().send_text(MAV_SEVERITY_INFO, "PL: target acquired %.1fm", rangefinder_alt_m); } _target_acquired = true; } @@ -396,22 +382,6 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va run_output_prediction(); } -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL - { - static uint32_t last_print_ms; - uint32_t now = AP_HAL::millis(); - if (now - last_print_ms >= 1000) { - last_print_ms = now; - float dist = 0; - get_target_distance_m(dist); - printf("PL: TA:%u pos=(%.1f,%.1f) d=%.1f\n", - _target_acquired, - _target_pos_rel_est_NE.x, - _target_pos_rel_est_NE.y, - dist); - } - } -#endif break; } } @@ -434,7 +404,7 @@ bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body) target_vec_unit_body = Rz*target_vec_unit_body; - DataFlash_Class::instance()->Log_Write("LOSM", "TimeUS,LOSx,LOSy,LOSz", "Qfff", AP_HAL::micros64(), target_vec_unit_body.x, target_vec_unit_body.y, target_vec_unit_body.z); + AP::logger().Write("LOSM", "TimeUS,LOSx,LOSy,LOSz", "Qfff", AP_HAL::micros64(), target_vec_unit_body.x, target_vec_unit_body.y, target_vec_unit_body.z); return true; } else { return false; @@ -453,7 +423,7 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, if (target_vec_valid && alt_valid) { float dist, alt; - Vector3f cam_pos_ned = inertial_data_delayed.Tbn * _cam_offset.get(); + Vector3f cam_pos_ned = inertial_data_delayed->Tbn * _cam_offset.get(); if (_backend->distance_to_target() > 0.0f) { dist = _backend->distance_to_target(); @@ -464,7 +434,8 @@ bool AC_PrecLand::construct_pos_meas_using_rangefinder(float rangefinder_alt_m, } // Compute target position relative to IMU - Vector3f imu_pos_ned = inertial_data_delayed.Tbn * AP::ins().get_imu_pos_offset(_ahrs.get_primary_accel_index()); + const AP_AHRS &ahrs = AP::ahrs(); + Vector3f imu_pos_ned = inertial_data_delayed->Tbn * AP::ins().get_imu_pos_offset(ahrs.get_primary_accel_index()); Vector3f cam_pos_ned_rel_imu = cam_pos_ned-imu_pos_ned; _target_pos_rel_meas_NED = Vector3f(target_vec_unit_ned.x*dist, target_vec_unit_ned.y*dist, alt) + cam_pos_ned_rel_imu; return true; @@ -479,8 +450,8 @@ void AC_PrecLand::run_output_prediction() Vector2f target_vel_rel_est_corrected_NE = _target_vel_rel_est_NE; // Predict forward from delayed time horizon - for (uint8_t i=1; i<_inertial_history.size(); i++) { - const struct inertial_data_frame_s& inertial_data = _inertial_history.peek(i); + for (uint8_t i=1; i<_inertial_history->available(); i++) { + const struct inertial_data_frame_s& inertial_data = *(*_inertial_history)[i]; target_vel_rel_est_corrected_NE.x -= inertial_data.correctedVehicleDeltaVelocityNED.x; target_vel_rel_est_corrected_NE.y -= inertial_data.correctedVehicleDeltaVelocityNED.y; target_pos_rel_est_corrected_NE.x += target_vel_rel_est_corrected_NE.x * inertial_data.dt; @@ -512,7 +483,7 @@ void AC_PrecLand::run_output_prediction() target_pos_rel_est_corrected_NE.x += land_ofs_ned_m.x; target_pos_rel_est_corrected_NE.y += land_ofs_ned_m.y; - const struct inertial_data_frame_s& latest_inertial_data = _inertial_history.peek(_inertial_history.size()-1); + const struct inertial_data_frame_s& latest_inertial_data = *(*_inertial_history)[_inertial_history->available()-1]; _target_pos_rel_out_NE += _target_vel_rel_est_NE * latest_inertial_data.dt; _target_vel_rel_out_NE += -Vector2f(latest_inertial_data.correctedVehicleDeltaVelocityNED.x, latest_inertial_data.correctedVehicleDeltaVelocityNED.y); diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 13d42d2db0..77c895c247 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -85,8 +85,6 @@ class AC_PrecLand // returns target velocity relative to vehicle bool get_target_velocity_relative_cms(Vector2f& ret); - bool get_height_above_target_cm(int32_t& ret); - // returns true when the landing target has been detected bool target_acquired(); From 1657406c8747cc3efee871f15fad89889fdf03d5 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 28 Feb 2017 17:03:48 -0800 Subject: [PATCH 017/155] AP_Motors: simplify current limiting feature This fixes a bug where current limiting could fail if the current voltage is less than MOT_BAT_VOLT_MIN --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 2c86268e31..d3989ce114 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -313,9 +313,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle() } // calculate the maximum current to prevent voltage sag below _batt_voltage_min - float batt_current_max = MIN(_batt_current_max, _batt_current + (battery.voltage(_batt_idx) - _batt_voltage_min) / _batt_resistance); - - float batt_current_ratio = _batt_current / batt_current_max; + float batt_current_ratio = _batt_current/_batt_current_max; float loop_interval = 1.0f / _loop_rate; _throttle_limit += (loop_interval / (loop_interval + _batt_current_time_constant)) * (1.0f - batt_current_ratio); From ae27d693b981f5465334930f93e654ca6b8d3b19 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 14 Apr 2017 14:30:37 -0700 Subject: [PATCH 018/155] AP_Motors: add frame type MATTERNET_M2 --- libraries/AP_Motors/AP_MotorsMatrix.cpp | 12 ++++++++++++ libraries/AP_Motors/AP_Motors_Class.h | 3 ++- 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 82129b56f4..65806a561f 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -503,6 +503,7 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty add_motor(AP_MOTORS_MOT_3, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); break; + case MOTOR_FRAME_TYPE_MATTERNET_M2: case MOTOR_FRAME_TYPE_X: add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); @@ -736,6 +737,17 @@ void AP_MotorsMatrix::setup_motors(motor_frame_class frame_class, motor_frame_ty add_motor(AP_MOTORS_MOT_7, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); add_motor(AP_MOTORS_MOT_8, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); break; + case MOTOR_FRAME_TYPE_MATTERNET_M2: + add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1); + add_motor(AP_MOTORS_MOT_3, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); + add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 5); + add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); + add_motor(AP_MOTORS_MOT_7, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); + add_motor(AP_MOTORS_MOT_5, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 2); + add_motor(AP_MOTORS_MOT_8, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); + add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); + success = true; + break; default: // octaquad frame class does not support this frame type success = false; diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 9e18d0a1fa..c518c50013 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -59,6 +59,7 @@ class AP_Motors { MOTOR_FRAME_TYPE_DJI_X = 13, // X frame, DJI ordering MOTOR_FRAME_TYPE_CW_X = 14, // X frame, clockwise ordering MOTOR_FRAME_TYPE_I = 15, // (sideways H) octo only + MOTOR_FRAME_TYPE_MATTERNET_M2 = 100, }; // Constructor @@ -263,4 +264,4 @@ class AP_Motors { namespace AP { AP_Motors *motors(); -}; \ No newline at end of file +}; From 51521459aa951d4c9332c94593f714a0ab36c555 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 1 Jun 2017 14:41:59 -0700 Subject: [PATCH 019/155] AP_Motors: add power limiting option --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 25 ++++++++++++++++---- libraries/AP_Motors/AP_MotorsMulticopter.h | 1 + 2 files changed, 22 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index d3989ce114..e20a4010c6 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -176,7 +176,13 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @User: Advanced AP_GROUPINFO("BOOST_SCALE", 37, AP_MotorsMulticopter, _boost_scale, 0), - // 38 RESERVED for BAT_POW_MAX + // @Param: BAT_POW_MAX + // @DisplayName: Motor Power Max + // @Description: Maximum power over which maximum throttle is limited (0 = Disabled) + // @Range: 0 20000 + // @Units: W + // @User: Advanced + AP_GROUPINFO("BAT_POW_MAX", 38, AP_MotorsMulticopter, _batt_power_max, 0), // @Param: BAT_IDX // @DisplayName: Battery compensation index @@ -296,9 +302,20 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle() { AP_BattMonitor &battery = AP::battery(); - float _batt_current; + float batt_voltage = constrain_float(battery.voltage(_batt_idx), _batt_voltage_min, _batt_voltage_max); - if (_batt_current_max <= 0 || // return maximum if current limiting is disabled + float batt_current_max = 0; + if (!is_zero(_batt_current_max) && !is_zero(_batt_power_max) && !is_zero(batt_voltage)) { + batt_current_max = MIN(_batt_current_max, _batt_power_max/batt_voltage); + } else if(!is_zero(_batt_power_max) && !is_zero(batt_voltage)) { + batt_current_max = _batt_power_max/batt_voltage; + } else if(!is_zero(_batt_current_max)) { + batt_current_max = _batt_current_max; + } + + // return maximum if current limiting is disabled + float _batt_current; + if (batt_current_max <= 0 || // return maximum if current limiting is disabled !_flags.armed || // remove throttle limit if disarmed !battery.current_amps(_batt_current, _batt_idx)) { // no current monitoring is available _throttle_limit = 1.0f; @@ -313,7 +330,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle() } // calculate the maximum current to prevent voltage sag below _batt_voltage_min - float batt_current_ratio = _batt_current/_batt_current_max; + float batt_current_ratio = _batt_current/batt_current_max; float loop_interval = 1.0f / _loop_rate; _throttle_limit += (loop_interval / (loop_interval + _batt_current_time_constant)) * (1.0f - batt_current_ratio); diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 2b2db7610d..e9fa727e26 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -163,6 +163,7 @@ class AP_MotorsMulticopter : public AP_Motors { AP_Float _throttle_hover; // estimated throttle required to hover throttle in the range 0 ~ 1 AP_Int8 _throttle_hover_learn; // enable/disabled hover thrust learning AP_Int8 _disarm_disable_pwm; // disable PWM output while disarmed + AP_Float _batt_power_max; // power over which maximum throttle is limited // Maximum lean angle of yaw servo in degrees. This is specific to tricopter AP_Float _yaw_servo_angle_max_deg; From 04c5ee30344ea0b49ef8eb459ab85dcf8fe235da Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 19 Jul 2017 11:02:52 -0700 Subject: [PATCH 020/155] AP_RangeFinder: add retries to MaxsonarI2CXL init --- .../AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index db30e18cdb..4a4acd6ba5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -62,7 +62,16 @@ AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeF return nullptr; } - if (!sensor->_init()) { + bool success = false; + for (uint8_t i=0; i<10; i++) { + if (sensor->_init()) { + success = true; + break; + } + hal.scheduler->delay(10); + } + + if (!success) { delete sensor; return nullptr; } From 67f81196e4bea9a8d555b5ba21d6d1f3163d45a6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 17 Feb 2020 17:48:19 +1100 Subject: [PATCH 021/155] AP_RangeFinder: check if a configured rangefinder is not giving data this extend the prearm_healthy() check for rangefinders to ensure that all configured rangefinders are getting data --- libraries/AP_RangeFinder/RangeFinder.cpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 99689b36d8..8a4ea81f87 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -687,9 +687,17 @@ void RangeFinder::Log_RFND() bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const { for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { - if ((params[i].type != RangeFinder_TYPE_NONE) && (drivers[i] == nullptr)) { - hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %d was not detected", i + 1); - return false; + if (params[i].type == RangeFinder_TYPE_NONE) { + continue; + } + if (drivers[i] == nullptr) { + hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %u was not detected", unsigned(i + 1)); + return false; + } + if (drivers[i]->status() == RangeFinder_NotConnected || + drivers[i]->status() == RangeFinder_NoData) { + hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %u unhealthy", unsigned(i + 1)); + return false; } } From 726497615e7bb3322ac53b0b11769c94dce4fe9f Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Thu, 14 Feb 2019 18:23:45 -0800 Subject: [PATCH 022/155] AP_GPS: Fixed issue: gps2 not logging data when unplugged whereas gps1 logging 0's on unplugging --- libraries/AP_GPS/AP_GPS.cpp | 21 +++++++++++++-------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index bbb58285f0..c63d8699ff 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1009,15 +1009,20 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) { static uint32_t last_send_time_ms[MAVLINK_COMM_NUM_BUFFERS]; - if (num_instances < 2 || status(1) <= AP_GPS::NO_GPS) { - return; - } - // when we have a GPS then only send new data - if (last_send_time_ms[chan] == last_message_time_ms(1)) { - return; + if (num_instances >= 2 && status(1) > AP_GPS::NO_GPS) { + // when we have a GPS then only send new data + if (last_send_time_ms[chan] == last_message_time_ms(1)) { + return; + } + last_send_time_ms[chan] = last_message_time_ms(1); + } else { + // when we don't have a GPS then send at 1Hz + uint32_t now = AP_HAL::millis(); + if (now - last_send_time_ms[chan] < 1000) { + return; + } + last_send_time_ms[chan] = now; } - last_send_time_ms[chan] = last_message_time_ms(1); - const Location &loc = location(1); mavlink_msg_gps2_raw_send( chan, From ec0ba01a96967e53edafed127a1726c114541051 Mon Sep 17 00:00:00 2001 From: Akshay Bajaj Date: Wed, 20 Feb 2019 17:17:54 -0800 Subject: [PATCH 023/155] AP_GPS: Changed the switch logic: switch only if the other GPS has 4 or more satellites for 5 sec. Earlier it was 2 or more sats --- libraries/AP_GPS/AP_GPS.cpp | 31 ++++++++++++++----------------- 1 file changed, 14 insertions(+), 17 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index c63d8699ff..c84c2a3a8a 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -795,27 +795,24 @@ void AP_GPS::update(void) } if (state[i].status > state[primary_instance].status) { // we have a higher status lock, or primary is set to the blended GPS, change GPS - primary_instance = i; - _last_instance_swap_ms = now; - continue; - } - - bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1); - - if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) { - - bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2); + + if (state[primary_instance].status < GPS_OK_FIX_3D) { + primary_instance = i; + _last_instance_swap_ms = now; + gcs().send_text(MAV_SEVERITY_CRITICAL, "GPS Switch: Switched to %u", primary_instance+1); + // add alert when a switch happens + continue; + } + // switch only if the currently used GPS has a 2D FIX or lower - if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) || - (another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) { - // this GPS has more satellites than the - // current primary, switch primary. Once we switch we will - // then tend to stick to the new GPS as primary. We don't - // want to switch too often as it will look like a - // position shift to the controllers. + if (state[i].status > GPS_OK_FIX_3D) { primary_instance = i; _last_instance_swap_ms = now; + gcs().send_text(MAV_SEVERITY_CRITICAL, "GPS Switch: Switched to %u", primary_instance+1); + // add alert when a switch happens + continue; } + // er if the other GPS has a DGPS FIX (the best possible fix) } } } From f3b61be09b189ee03123004401d852662699374b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2019 12:16:37 +1000 Subject: [PATCH 024/155] AP_GPS: add tracking of position change since arming used as part of pre-takeoff checks for auto takeoff --- libraries/AP_GPS/AP_GPS.cpp | 30 ++++++++++++++++++++++++++++++ libraries/AP_GPS/AP_GPS.h | 14 ++++++++++++++ 2 files changed, 44 insertions(+) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index c84c2a3a8a..62450ef036 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -723,6 +723,7 @@ void AP_GPS::update_instance(uint8_t instance) if (now != 0) { AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS); } + update_position_change(instance); } #else (void)data_should_be_logged; @@ -1658,6 +1659,35 @@ bool AP_GPS::prepare_for_arming(void) { return all_passed; } +/* + update data for distance moved since arming. Used for pre-takeoff + check + */ +void AP_GPS::update_position_change(uint8_t instance) +{ + if (!hal.util->get_soft_armed()) { + _arm_loc[instance].lat = 0; + _arm_loc[instance].lng = 0; + } else if (_arm_loc[instance].lat == 0 && + _arm_loc[instance].lng == 0) { + _arm_loc[instance] = state[instance].location; + } +} + +/* + get change in position and altitude since arming + This is used as part of a pre-takeoff check for GPS movement +*/ +bool AP_GPS::get_pre_arm_pos_change(uint8_t instance, float &pos_change, float &alt_change) const +{ + if (!hal.util->get_soft_armed()) { + return false; + } + pos_change = get_distance(_arm_loc[instance], state[instance].location); + alt_change = (_arm_loc[instance].alt - state[instance].location.alt) * 0.01; + return true; +} + namespace AP { AP_GPS &gps() diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 50481ef234..79acc60c7c 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -439,6 +439,12 @@ class AP_GPS // handle possibly fragmented RTCM injection data void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len); + // get change in position and altitude since arming + bool get_pre_arm_pos_change(uint8_t instance, float &pos_change, float &alt_change) const; + bool get_pre_arm_pos_change(float &pos_change, float &alt_change) const { + return get_pre_arm_pos_change(primary_instance, pos_change, alt_change); + } + protected: // configuration parameters @@ -524,6 +530,8 @@ class AP_GPS void detect_instance(uint8_t instance); void update_instance(uint8_t instance); + void update_position_change(uint8_t instance); + /* buffer for re-assembling RTCM data for GPS injection. The 8 bit flags field in GPS_RTCM_DATA is interpreted as: @@ -563,6 +571,12 @@ class AP_GPS bool _output_is_blended; // true when a blended GPS solution being output uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy + /* + track change in position and height since arming. Used for + pre-takeoff check + */ + Location _arm_loc[GPS_MAX_RECEIVERS]; + // calculate the blend weight. Returns true if blend could be calculated, false if not bool calc_blend_weights(void); From 3eb981e0ad88324d838eb535707b4e3fe1bbc0bd Mon Sep 17 00:00:00 2001 From: AkshayMatternet Date: Thu, 18 Jul 2019 15:41:06 -0700 Subject: [PATCH 025/155] AP_GPS: Added hardware_version method --- libraries/AP_GPS/AP_GPS_UBLOX.h | 5 +++++ libraries/AP_GPS/GPS_Backend.h | 3 +++ 2 files changed, 8 insertions(+) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 15f7ab4eb1..04026c2c32 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -671,4 +671,9 @@ class AP_GPS_UBLOX : public AP_GPS_Backend uint8_t _ubx_msg_log_index(uint8_t ubx_msg) { return (uint8_t)(ubx_msg + (state.instance * UBX_MSG_TYPES)); } + + // returns hardware generation of the GPS + uint32_t hardware_generation() { + return _hardware_generation; + } }; diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index 973d7611aa..4bff2a8195 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -65,6 +65,9 @@ class AP_GPS_Backend virtual bool prepare_for_arming(void) { return true; } + // returns hardware generation variable + virtual uint32_t hardware_generation() { return 0; } + protected: AP_HAL::UARTDriver *port; ///< UART we are attached to AP_GPS &gps; ///< access to frontend (for parameters) From d70a3d707c12bb8f048ce1a8a87c19af20c44724 Mon Sep 17 00:00:00 2001 From: AkshayMatternet Date: Thu, 18 Jul 2019 19:27:43 -0700 Subject: [PATCH 026/155] AP_GPS: Prefer u-blox F9P --- libraries/AP_GPS/AP_GPS.cpp | 49 +++++++++++++++++++-------------- libraries/AP_GPS/AP_GPS_UBLOX.h | 23 ++++++++-------- libraries/AP_GPS/GPS_Backend.h | 2 +- 3 files changed, 42 insertions(+), 32 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 62450ef036..71e48d7ee3 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -794,26 +794,35 @@ void AP_GPS::update(void) if (i == primary_instance) { continue; } - if (state[i].status > state[primary_instance].status) { - // we have a higher status lock, or primary is set to the blended GPS, change GPS - - if (state[primary_instance].status < GPS_OK_FIX_3D) { - primary_instance = i; - _last_instance_swap_ms = now; - gcs().send_text(MAV_SEVERITY_CRITICAL, "GPS Switch: Switched to %u", primary_instance+1); - // add alert when a switch happens - continue; - } - // switch only if the currently used GPS has a 2D FIX or lower - - if (state[i].status > GPS_OK_FIX_3D) { - primary_instance = i; - _last_instance_swap_ms = now; - gcs().send_text(MAV_SEVERITY_CRITICAL, "GPS Switch: Switched to %u", primary_instance+1); - // add alert when a switch happens - continue; - } - // er if the other GPS has a DGPS FIX (the best possible fix) + + GPS_Status status_i = state[i].status; + GPS_Status status_primary = state[primary_instance].status; + + + // Treat U-blox F9 as SBAS if it has more than or equal to 16 satellites, as it is dual band GPS and is more accurate than M8 with SBAS + if (status_i == GPS_OK_FIX_3D && state[i].num_sats >= 16 && strcmp(drivers[i]->name(), "u-blox") == 0 && drivers[i]->hardware_generation() == AP_GPS_UBLOX::UBLOX_F9) { + status_i = GPS_OK_FIX_3D_DGPS; + } + + // Treat U-blox F9 as SBAS if it has more than or equal to 16 satellites, as it is dual band GPS and is more accurate than M8 with SBAS + if (status_primary == GPS_OK_FIX_3D && state[primary_instance].num_sats >= 16 && strcmp(drivers[primary_instance]->name(), "u-blox") == 0 && drivers[primary_instance]->hardware_generation() == AP_GPS_UBLOX::UBLOX_F9) { + status_primary = GPS_OK_FIX_3D_DGPS; + } + + bool should_switch = false; + + if (status_i > status_primary) { + should_switch = true; + } + + else if (status_i == status_primary && !hal.util->get_soft_armed() && state[i].num_sats >= state[primary_instance].num_sats+3) { + should_switch = true; + } + + if (should_switch) { + primary_instance = i; + _last_instance_swap_ms = now; + gcs().send_text(MAV_SEVERITY_CRITICAL, "GPS Switch: Switched to %u", primary_instance+1); } } } diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 04026c2c32..93ed4e7500 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -128,6 +128,17 @@ class AP_GPS_UBLOX : public AP_GPS_Backend const char *name() const override { return "u-blox"; } + enum ubx_hardware_version { + ANTARIS = 0, + UBLOX_5, + UBLOX_6, + UBLOX_7, + UBLOX_M8, + UBLOX_F9 = 0x80, // comes from MON_VER hwVersion string + UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for + // flagging state in the driver + }; + private: // u-blox UBX protocol essentials struct PACKED ubx_header { @@ -564,16 +575,6 @@ class AP_GPS_UBLOX : public AP_GPS_Backend NAV_STATUS_FIX_VALID = 1, NAV_STATUS_DGPS_USED = 2 }; - enum ubx_hardware_version { - ANTARIS = 0, - UBLOX_5, - UBLOX_6, - UBLOX_7, - UBLOX_M8, - UBLOX_F9 = 0x80, // comes from MON_VER hwVersion string - UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for - // flagging state in the driver - }; enum config_step { STEP_PVT = 0, @@ -673,7 +674,7 @@ class AP_GPS_UBLOX : public AP_GPS_Backend } // returns hardware generation of the GPS - uint32_t hardware_generation() { + uint32_t hardware_generation() const override { return _hardware_generation; } }; diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index 4bff2a8195..0dd60f3e30 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -66,7 +66,7 @@ class AP_GPS_Backend virtual bool prepare_for_arming(void) { return true; } // returns hardware generation variable - virtual uint32_t hardware_generation() { return 0; } + virtual uint32_t hardware_generation() const { return 0; } protected: AP_HAL::UARTDriver *port; ///< UART we are attached to From 8c8afb2a03de43eec33228dd182f72df0218c960 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 24 Oct 2019 13:17:09 +1100 Subject: [PATCH 027/155] AP_GPS: prefer UAVCAN status 3 over M8 status 4 this fixes preferance of GPS for 1st UAVCAN, 2nd M8 UART --- libraries/AP_GPS/AP_GPS.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 71e48d7ee3..50f110616a 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -797,7 +797,16 @@ void AP_GPS::update(void) GPS_Status status_i = state[i].status; GPS_Status status_primary = state[primary_instance].status; - + + if (_type[i] == GPS_TYPE_UAVCAN && _type[1-i] != GPS_TYPE_UAVCAN && status_i == GPS_OK_FIX_3D) { + // if this is a UAVCAN GPS and the other GPS + // is not UAVCAN then we don't know what type + // it is. It is likely F9, so make status=3 be + // equal to status=4 for comparison purposes + // so we choose it over a 2nd M8 with SBAS + // lock + status_i = GPS_OK_FIX_3D_DGPS; + } // Treat U-blox F9 as SBAS if it has more than or equal to 16 satellites, as it is dual band GPS and is more accurate than M8 with SBAS if (status_i == GPS_OK_FIX_3D && state[i].num_sats >= 16 && strcmp(drivers[i]->name(), "u-blox") == 0 && drivers[i]->hardware_generation() == AP_GPS_UBLOX::UBLOX_F9) { From cd07418a0f167184dc0411f7580191b9fc48d96b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 17 Feb 2020 17:48:18 +1100 Subject: [PATCH 028/155] AP_GPS: added zero yaw value for new mavlink GPS msgs --- libraries/AP_GPS/AP_GPS.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 50f110616a..8d6395fba8 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1018,7 +1018,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s - 0); // TODO one-sigma heading accuracy standard deviation + 0, 0); // TODO one-sigma heading accuracy standard deviation } #if GPS_MAX_RECEIVERS > 1 @@ -1053,7 +1053,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) ground_course(1)*100, // 1/100 degrees, num_sats(1), state[1].rtk_num_sats, - state[1].rtk_age_ms); + state[1].rtk_age_ms, 0); } #endif // GPS_MAX_RECEIVERS @@ -1701,7 +1701,7 @@ bool AP_GPS::get_pre_arm_pos_change(uint8_t instance, float &pos_change, float & if (!hal.util->get_soft_armed()) { return false; } - pos_change = get_distance(_arm_loc[instance], state[instance].location); + pos_change = _arm_loc[instance].get_distance(state[instance].location); alt_change = (_arm_loc[instance].alt - state[instance].location.alt) * 0.01; return true; } From 73d7544bc0164a4c258b463ff3e279207da0977c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 16 Feb 2020 07:24:36 +1100 Subject: [PATCH 029/155] AP_UAVCAN: removed ArduPilot TrafficReport DSDL --- .../trafficmonitor/20790.TrafficReport.uavcan | 68 ------------------- 1 file changed, 68 deletions(-) delete mode 100644 libraries/AP_UAVCAN/dsdl/ardupilot/equipment/trafficmonitor/20790.TrafficReport.uavcan diff --git a/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/trafficmonitor/20790.TrafficReport.uavcan b/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/trafficmonitor/20790.TrafficReport.uavcan deleted file mode 100644 index 281b30928f..0000000000 --- a/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/trafficmonitor/20790.TrafficReport.uavcan +++ /dev/null @@ -1,68 +0,0 @@ -# Network-synchronized timestamp, 0 if not available. Note: not necessarily a UTC time. -uavcan.Timestamp timestamp - -# icao address -uint32 icao_address - -# Time since last communication in seconds -uint16 tslc - -# Traffic position in lat-lon-alt. Check alt_type for altitude datum -int32 latitude_deg_1e7 -int32 longitude_deg_1e7 -float32 alt_m - -# Traffic heading in radians. -# Course over ground if heading is unavailable. 0 if neither are available. -float16 heading - -# Traffic velocity in m/s -float16[3] velocity - -# Traffic squawk code -uint16 squawk - -# Traffic callsign -uint8[9] callsign - -# Traffic source -uint3 SOURCE_ADSB = 0 -uint3 SOURCE_ADSB_UAT = 1 -uint3 SOURCE_FLARM = 2 -uint3 source - -# Traffic type -uint5 TRAFFIC_TYPE_UNKNOWN = 0 -uint5 TRAFFIC_TYPE_LIGHT = 1 -uint5 TRAFFIC_TYPE_SMALL = 2 -uint5 TRAFFIC_TYPE_LARGE = 3 -uint5 TRAFFIC_TYPE_HIGH_VORTEX_LARGE = 4 -uint5 TRAFFIC_TYPE_HEAVY = 5 -uint5 TRAFFIC_TYPE_HIGHLY_MANUV = 6 -uint5 TRAFFIC_TYPE_ROTOCRAFT = 7 -uint5 TRAFFIC_TYPE_GLIDER = 9 -uint5 TRAFFIC_TYPE_LIGHTER_THAN_AIR = 10 -uint5 TRAFFIC_TYPE_PARACHUTE = 11 -uint5 TRAFFIC_TYPE_ULTRA_LIGHT = 12 -uint5 TRAFFIC_TYPE_UAV = 14 -uint5 TRAFFIC_TYPE_SPACE = 15 -uint5 TRAFFIC_TYPE_EMERGENCY_SURFACE = 17 -uint5 TRAFFIC_TYPE_SERVICE_SURFACE = 18 -uint5 TRAFFIC_TYPE_POINT_OBSTACLE = 19 -uint5 traffic_type - -# Altitude type -uint7 ALT_TYPE_ALT_UNKNOWN = 0 -uint7 ALT_TYPE_PRESSURE_AMSL = 1 -uint7 ALT_TYPE_WGS84 = 2 -uint7 alt_type - -# Validity flags -bool lat_lon_valid -bool heading_valid -bool velocity_valid -bool callsign_valid -bool ident_valid -bool simulated_report -bool vertical_velocity_valid -bool baro_valid From 21f8244140234c951f24243af7d71fc2a45b1abb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 2 Oct 2019 19:44:16 +1000 Subject: [PATCH 030/155] AP_UAVCAN: added Matternet TrafficReport message --- .../trafficmonitor/20790.TrafficReport.uavcan | 68 +++++++++++++++++++ 1 file changed, 68 insertions(+) create mode 100644 libraries/AP_UAVCAN/dsdl/com/matternet/equipment/trafficmonitor/20790.TrafficReport.uavcan diff --git a/libraries/AP_UAVCAN/dsdl/com/matternet/equipment/trafficmonitor/20790.TrafficReport.uavcan b/libraries/AP_UAVCAN/dsdl/com/matternet/equipment/trafficmonitor/20790.TrafficReport.uavcan new file mode 100644 index 0000000000..281b30928f --- /dev/null +++ b/libraries/AP_UAVCAN/dsdl/com/matternet/equipment/trafficmonitor/20790.TrafficReport.uavcan @@ -0,0 +1,68 @@ +# Network-synchronized timestamp, 0 if not available. Note: not necessarily a UTC time. +uavcan.Timestamp timestamp + +# icao address +uint32 icao_address + +# Time since last communication in seconds +uint16 tslc + +# Traffic position in lat-lon-alt. Check alt_type for altitude datum +int32 latitude_deg_1e7 +int32 longitude_deg_1e7 +float32 alt_m + +# Traffic heading in radians. +# Course over ground if heading is unavailable. 0 if neither are available. +float16 heading + +# Traffic velocity in m/s +float16[3] velocity + +# Traffic squawk code +uint16 squawk + +# Traffic callsign +uint8[9] callsign + +# Traffic source +uint3 SOURCE_ADSB = 0 +uint3 SOURCE_ADSB_UAT = 1 +uint3 SOURCE_FLARM = 2 +uint3 source + +# Traffic type +uint5 TRAFFIC_TYPE_UNKNOWN = 0 +uint5 TRAFFIC_TYPE_LIGHT = 1 +uint5 TRAFFIC_TYPE_SMALL = 2 +uint5 TRAFFIC_TYPE_LARGE = 3 +uint5 TRAFFIC_TYPE_HIGH_VORTEX_LARGE = 4 +uint5 TRAFFIC_TYPE_HEAVY = 5 +uint5 TRAFFIC_TYPE_HIGHLY_MANUV = 6 +uint5 TRAFFIC_TYPE_ROTOCRAFT = 7 +uint5 TRAFFIC_TYPE_GLIDER = 9 +uint5 TRAFFIC_TYPE_LIGHTER_THAN_AIR = 10 +uint5 TRAFFIC_TYPE_PARACHUTE = 11 +uint5 TRAFFIC_TYPE_ULTRA_LIGHT = 12 +uint5 TRAFFIC_TYPE_UAV = 14 +uint5 TRAFFIC_TYPE_SPACE = 15 +uint5 TRAFFIC_TYPE_EMERGENCY_SURFACE = 17 +uint5 TRAFFIC_TYPE_SERVICE_SURFACE = 18 +uint5 TRAFFIC_TYPE_POINT_OBSTACLE = 19 +uint5 traffic_type + +# Altitude type +uint7 ALT_TYPE_ALT_UNKNOWN = 0 +uint7 ALT_TYPE_PRESSURE_AMSL = 1 +uint7 ALT_TYPE_WGS84 = 2 +uint7 alt_type + +# Validity flags +bool lat_lon_valid +bool heading_valid +bool velocity_valid +bool callsign_valid +bool ident_valid +bool simulated_report +bool vertical_velocity_valid +bool baro_valid From 6dd6f16d4ec4acf3c1fabbbaa504340a5e96a090 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Oct 2019 22:10:08 +1100 Subject: [PATCH 031/155] AP_UAVCAN: added DSDL for GNSS Inject message for passing MAVLink GPS_INJECT onto UAVCAN GPS modules --- .../dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan diff --git a/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan b/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan new file mode 100644 index 0000000000..10b5dcc07e --- /dev/null +++ b/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan @@ -0,0 +1,8 @@ +# +# GNSS Inject, used by autopilots to forward GPS_RTCM_DATA or GPS_INJECT mavlink msgs +# to GNSS nodes. Normally sent as broadcast + +# flags follows the same conventions as MAVLink GPS_RTCM_DATA +uint8 flags + +uint8[<=180] data From ec2a52d40b33f3529086a797c8c7deee4fedc73c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 17 Feb 2020 17:48:19 +1100 Subject: [PATCH 032/155] AP_UAVCAN: change to MatterNet TrafficReport namespace --- libraries/AP_UAVCAN/AP_UAVCAN.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.cpp b/libraries/AP_UAVCAN/AP_UAVCAN.cpp index 71344918d0..5336b57862 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN.cpp @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include @@ -118,8 +118,8 @@ UC_REGISTRY_BINDER(ButtonCb, ardupilot::indication::Button); static uavcan::Subscriber *safety_button_listener[MAX_NUMBER_OF_CAN_DRIVERS]; // handler TrafficReport -UC_REGISTRY_BINDER(TrafficReportCb, ardupilot::equipment::trafficmonitor::TrafficReport); -static uavcan::Subscriber *traffic_report_listener[MAX_NUMBER_OF_CAN_DRIVERS]; +UC_REGISTRY_BINDER(TrafficReportCb, com::matternet::equipment::trafficmonitor::TrafficReport); +static uavcan::Subscriber *traffic_report_listener[MAX_NUMBER_OF_CAN_DRIVERS]; // handler actuator status UC_REGISTRY_BINDER(ActuatorStatusCb, uavcan::equipment::actuator::Status); @@ -278,7 +278,7 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) safety_button_listener[driver_index]->start(ButtonCb(this, &handle_button)); } - traffic_report_listener[driver_index] = new uavcan::Subscriber(*_node); + 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)); } @@ -676,7 +676,7 @@ 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]; + const com::matternet::equipment::trafficmonitor::TrafficReport &msg = cb.msg[0]; AP_ADSB::adsb_vehicle_t vehicle; mavlink_adsb_vehicle_t &pkt = vehicle.info; @@ -694,10 +694,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 == com::matternet::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 == com::matternet::equipment::trafficmonitor::TrafficReport::ALT_TYPE_WGS84) { pkt.flags |= ADSB_FLAGS_VALID_ALTITUDE; pkt.altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC; } From 29802cebfd4f12d4b7b18895a11d693a008e1a58 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 24 Jun 2016 15:39:59 -0700 Subject: [PATCH 033/155] GCS_MAVLink: add MSG_LANDING_TARGET to enum --- libraries/GCS_MAVLink/ap_message.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index a50041162a..a5cd7b9022 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -71,6 +71,7 @@ enum ap_message : uint8_t { MSG_ORIGIN, MSG_HOME, MSG_NAMED_FLOAT, + MSG_LANDING_TARGET, MSG_EXTENDED_SYS_STATE, MSG_AUTOPILOT_VERSION, MSG_LAST // MSG_LAST must be the last entry in this enum From f886fc6ed4c173e57668d4b39500ada67d328538 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 2 Oct 2019 11:22:34 +1000 Subject: [PATCH 034/155] AP_Logger: re-write system IDs and params when disarming this ensures that logs have system IDs even when trimmed. The IDs will be in the log twice, once on first arm, and again when disarming --- libraries/AP_Logger/AP_Logger_File.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index b5b2a32948..125799296e 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -1084,6 +1084,9 @@ void AP_Logger_File::vehicle_was_disarmed() // logging restart naturally based on log_disarmed should do // the trick: _rotate_pending = true; + + // write out all of our system ID and vars again at end of log + start_new_log_reset_variables(); } } From 3525a2293333f8563161a744346a10e5699de883 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 20 Jul 2016 11:39:34 -0700 Subject: [PATCH 035/155] AC_PosControl: change hard-coded tuning values --- libraries/AC_AttitudeControl/AC_PosControl.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 6384a4dfb1..cc3899e645 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -19,6 +19,7 @@ #define POSCONTROL_ACCEL_XY_MAX 980.0f // max horizontal acceleration in cm/s/s that the position velocity controller will ask from the lower accel controller #define POSCONTROL_STOPPING_DIST_UP_MAX 300.0f // max stopping distance (in cm) vertically while climbing #define POSCONTROL_STOPPING_DIST_DOWN_MAX 200.0f // max stopping distance (in cm) vertically while descending +#define POSCONTROL_JERK_LIMIT_CMSSS 3400.0f // default jerk limit on horizontal acceleration (unit: m/s/s/s) #define POSCONTROL_SPEED 500.0f // default horizontal speed in cm/s #define POSCONTROL_SPEED_DOWN -150.0f // default descent rate in cm/s @@ -35,8 +36,8 @@ #define POSCONTROL_VEL_ERROR_CUTOFF_FREQ 4.0f // low-pass filter on velocity error (unit: hz) #define POSCONTROL_THROTTLE_CUTOFF_FREQ 2.0f // low-pass filter on accel error (unit: hz) -#define POSCONTROL_ACCEL_FILTER_HZ 2.0f // low-pass filter on acceleration (unit: hz) -#define POSCONTROL_JERK_RATIO 1.0f // Defines the time it takes to reach the requested acceleration +#define POSCONTROL_ACCEL_FILTER_HZ 3.0f // low-pass filter on acceleration (unit: hz) +#define POSCONTROL_JERK_RATIO 2.0f // Defines the time it takes to reach the requested acceleration #define POSCONTROL_OVERSPEED_GAIN_Z 2.0f // gain controlling rate at which z-axis speed is brought back within SPEED_UP and SPEED_DOWN range From 598464e74b52d666d2fbe401337f8b7963181a51 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 11 Nov 2016 11:17:26 -0800 Subject: [PATCH 036/155] AP_SerialManager: add Matternet_FTS protocol --- libraries/AP_SerialManager/AP_SerialManager.cpp | 7 +++++++ libraries/AP_SerialManager/AP_SerialManager.h | 5 +++++ libraries/GCS_MAVLink/GCS.h | 3 +++ libraries/GCS_MAVLink/GCS_Common.cpp | 12 ++++++++++++ 4 files changed, 27 insertions(+) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 93e2f681a1..f3e067be2c 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -454,6 +454,13 @@ void AP_SerialManager::init() state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); break; + case SerialProtocol_Matternet_FTS: + state[i].baud = AP_SERIALMANAGER_MATTERNET_FTS_BAUD / 1000; // update baud param in case user looks at it + state[i].uart->begin(map_baudrate(state[i].baud), + AP_SERIALMANAGER_MATTERNET_FTS_BUFSIZE_RX, + AP_SERIALMANAGER_MATTERNET_FTS_BUFSIZE_TX); + break; + case SerialProtocol_Robotis: state[i].uart->begin(map_baudrate(state[i].baud), AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX, diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index f0517bf167..c8ff0555da 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -89,6 +89,10 @@ #define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128 #define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128 +#define AP_SERIALMANAGER_MATTERNET_FTS_BAUD 115200 +#define AP_SERIALMANAGER_MATTERNET_FTS_BUFSIZE_RX 64 +#define AP_SERIALMANAGER_MATTERNET_FTS_BUFSIZE_TX 64 + class AP_SerialManager { public: AP_SerialManager(); @@ -123,6 +127,7 @@ class AP_SerialManager { SerialProtocol_WindVane = 21, SerialProtocol_SLCAN = 22, SerialProtocol_RCIN = 23, + SerialProtocol_Matternet_FTS = 100, }; // get singleton instance diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 265768bc91..65c9387d73 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -229,6 +229,9 @@ class GCS_MAVLINK // don't get broadcast packets or forwarded packets static void set_channel_private(mavlink_channel_t chan); + // send a message to all active MAVLink connections + static void send_on_all_channels(const mavlink_message_t* msg); + // return true if channel is private static bool is_private(mavlink_channel_t _chan) { return (mavlink_private & (1U<<(unsigned)_chan)) != 0; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index d1c6bf875f..a54a9a02d4 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1848,6 +1848,18 @@ void GCS::service_statustext(void) } } +void GCS_MAVLINK::send_on_all_channels(const mavlink_message_t* msg) +{ + for (uint8_t i=0; i= ((uint16_t)msg->len) + GCS_MAVLINK::packet_overhead_chan(chan)) { + _mavlink_resend_uart(chan, msg); + } + } + } +} + void GCS::send_message(enum ap_message id) { for (uint8_t i=0; i Date: Mon, 14 Nov 2016 12:35:07 -0800 Subject: [PATCH 037/155] AP_Parachute: add TRIGGER_TYPE_MATTERNET_FTS --- libraries/AP_Parachute/AP_Parachute.cpp | 117 +++++++++++++++- libraries/AP_Parachute/AP_Parachute.h | 23 ++++ libraries/AP_Parachute/messages.h | 88 ++++++++++++ libraries/AP_Parachute/protocol.cpp | 176 ++++++++++++++++++++++++ libraries/AP_Parachute/protocol.h | 11 ++ libraries/AP_Parachute/slip.h | 67 +++++++++ 6 files changed, 481 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_Parachute/messages.h create mode 100644 libraries/AP_Parachute/protocol.cpp create mode 100644 libraries/AP_Parachute/protocol.h create mode 100644 libraries/AP_Parachute/slip.h diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 684ee77e5d..b742a1799e 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -8,10 +8,11 @@ #include #include +#include "protocol.h" + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Parachute::var_info[] = { - // @Param: ENABLED // @DisplayName: Parachute release enabled or disabled // @Description: Parachute release enabled or disabled @@ -159,6 +160,120 @@ void AP_Parachute::update() // update AP_Notify AP_Notify::flags.parachute_release = 0; } + + + if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_MATTERNET_FTS) { + mttr_fts_update(); + } +} + +void AP_Parachute::mttr_fts_transmit(uint8_t msg_len, uint8_t* msg_buf) +{ + if (!_mttr_uart) { + return; + } + + uint8_t encoded_msg[32]; + uint8_t encoded_msg_len = fts_protocol_encode_message(msg_len, msg_buf, 32, encoded_msg); + if (_mttr_uart->txspace() >= encoded_msg_len) { + _mttr_uart->write(encoded_msg, encoded_msg_len); + } +} + +void AP_Parachute::send_debug_message(uint32_t tnow_ms, uint8_t ind, float value) +{ + mavlink_message_t mav_msg; + mavlink_debug_t mav_dbg_msg; + mav_dbg_msg.time_boot_ms = tnow_ms; + mav_dbg_msg.ind = ind; + mav_dbg_msg.value = value; + mavlink_msg_debug_encode(mavlink_system.sysid, mavlink_system.compid, &mav_msg, &mav_dbg_msg); + GCS_MAVLINK::send_on_all_channels(&mav_msg); +} + +void AP_Parachute::mttr_fts_update() +{ + if (!_mttr_uart) { + return; + } + + uint32_t tnow_ms = AP_HAL::millis(); + + // 20Hz + if (tnow_ms - _mttr_last_loop_ms > 50) { + if (_release_in_progress || _released) { + struct fts_msg_deploy_s deploy_msg; + deploy_msg.msgid = FTS_MSGID_DEPLOY; + deploy_msg.magic = FTS_DEPLOY_MAGIC; + mttr_fts_transmit(sizeof(deploy_msg), (uint8_t*)&deploy_msg); + } + + if (tnow_ms - _mttr_last_status_recv_ms > 1000) { + _mttr_status_pass = false; + } + + struct fts_msg_wdrst_s wdrst_msg; + wdrst_msg.msgid = FTS_MSGID_WDRST; + mttr_fts_transmit(sizeof(wdrst_msg), (uint8_t*)&wdrst_msg); + + if (!_release_initiated) { + if (hal.util->get_soft_armed()) { + struct fts_msg_arm_cmd_s arm_msg; + arm_msg.msgid = FTS_MSGID_ARM_CMD; + mttr_fts_transmit(sizeof(arm_msg), (uint8_t*)&arm_msg); + } else { + struct fts_msg_disarm_cmd_s disarm_msg; + disarm_msg.msgid = FTS_MSGID_DISARM_CMD; + mttr_fts_transmit(sizeof(disarm_msg), (uint8_t*)&disarm_msg); + } + } + + _mttr_last_loop_ms = tnow_ms; + } + + uint8_t msg_buf[32]; + int16_t byte; + + while ((byte = _mttr_uart->read()) != -1) { + uint8_t msg_len = fts_protocol_rx_byte(byte, 32, msg_buf); + if (msg_len > 0) { + enum fts_msg_id_t msg_id = fts_protocol_identify_message(msg_len, msg_buf); + if (msg_id == FTS_MSGID_STATUS) { + struct fts_msg_status_s* msg = (struct fts_msg_status_s*)msg_buf; + AP::logger().Write("FTSS", "TimeUS,State,Rsn,BSoC,BC1mV,BC2mV,BC3mV,BTINT,BTTS1", "QBBBHHHcc", AP_HAL::micros64(), msg->state, msg->state_reason, msg->batt_SoC, msg->batt_cell_mV[0], msg->batt_cell_mV[1], msg->batt_cell_mV[2], msg->batt_temp_INT, msg->batt_temp_TS1); + + // update pre-arm state + _mttr_last_status_recv_ms = tnow_ms; + _mttr_status_pass = (msg->state == FTS_DISARMED_MASTER_PRESENT || msg->state == FTS_ARMED); + + // send via MAVLink + send_debug_message(tnow_ms, 0, msg->state); + send_debug_message(tnow_ms, 1, msg->state_reason); + send_debug_message(tnow_ms, 2, msg->batt_SoC); + send_debug_message(tnow_ms, 3, msg->batt_cell_mV[0]*1e-3f); + send_debug_message(tnow_ms, 4, msg->batt_cell_mV[1]*1e-3f); + send_debug_message(tnow_ms, 5, msg->batt_cell_mV[2]*1e-3f); + send_debug_message(tnow_ms, 6, msg->batt_temp_INT*1e-2f); + send_debug_message(tnow_ms, 7, msg->batt_temp_TS1*1e-2f); + + } else if (msg_id == FTS_MSGID_VERSION) { + struct fts_msg_version_s* msg = (struct fts_msg_version_s*)msg_buf; + memset(_mttr_fts_version, 0, sizeof(_mttr_fts_version)); + memcpy(_mttr_fts_version, msg->git_hash, sizeof(msg->git_hash)); + AP::logger().Write("FTSV", "TimeUS,Hash", "QN", AP_HAL::micros64(), _mttr_fts_version); + } else if (msg_id == FTS_MSGID_STATUS2) { + struct fts_msg_status2_s* msg = (struct fts_msg_status2_s*)msg_buf; + + _mttr_fuse_pass = (msg->fuse_fault_state == FTS_FUSE_STATE_PASS); + + AP::logger().Write("FTS2", "TimeUS,Fuse,WDTm", "QBh", AP_HAL::micros64(), msg->fuse_fault_state, msg->wdt_min_margin_ms); + + // send via MAVLink + send_debug_message(tnow_ms, 8, msg->fuse_fault_state); + send_debug_message(tnow_ms, 9, msg->wdt_min_margin_ms); + } + } + } } // singleton instance diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index 4280fb6df8..e80c7729ec 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -5,12 +5,14 @@ #include #include #include +#include #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_0 0 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_1 1 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_2 2 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_3 3 #define AP_PARACHUTE_TRIGGER_TYPE_SERVO 10 +#define AP_PARACHUTE_TRIGGER_TYPE_MATTERNET_FTS 11 #define AP_PARACHUTE_RELEASE_DELAY_MS 500 // delay in milliseconds between call to release() and when servo or relay actually moves. Allows for warning to user #define AP_PARACHUTE_RELEASE_DURATION_MS 2000 // when parachute is released, servo or relay stay at their released position/value for 2000ms (2seconds) @@ -30,6 +32,7 @@ class AP_Parachute { /// Constructor AP_Parachute(AP_Relay &relay) : _relay(relay) + , _mttr_fuse_pass(true) { // setup parameter defaults #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -39,12 +42,18 @@ class AP_Parachute { #endif _singleton = this; AP_Param::setup_object_defaults(this, var_info); + + strcpy(_mttr_fts_version, "UNKNOWN"); } /* Do not allow copies */ AP_Parachute(const AP_Parachute &other) = delete; AP_Parachute &operator=(const AP_Parachute&) = delete; + void init(AP_SerialManager& serial_manager) { + _mttr_uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Matternet_FTS, 0); + } + /// enabled - enable or disable parachute release void enabled(bool on_off); @@ -79,6 +88,9 @@ class AP_Parachute { // set_sink_rate - set vehicle sink rate void set_sink_rate(float sink_rate) { _sink_rate = sink_rate; } + const char* mttr_get_fts_version() { return _mttr_fts_version; } + bool get_mttr_prearm_pass() { return _mttr_status_pass && _mttr_fuse_pass; } + static const struct AP_Param::GroupInfo var_info[]; // get singleton instance @@ -104,6 +116,17 @@ class AP_Parachute { bool _is_flying:1; // true if the vehicle is flying float _sink_rate; // vehicle sink rate in m/s uint32_t _sink_time; // time that the vehicle exceeded critical sink rate + + // Matternet FTS + uint32_t _mttr_last_loop_ms; + uint32_t _mttr_last_status_recv_ms; + bool _mttr_status_pass; + bool _mttr_fuse_pass; + AP_HAL::UARTDriver *_mttr_uart = nullptr; + char _mttr_fts_version[16]; + void send_debug_message(uint32_t tnow_ms, uint8_t ind, float value); + void mttr_fts_transmit(uint8_t msg_len, uint8_t* msg_buf); + void mttr_fts_update(); }; namespace AP { diff --git a/libraries/AP_Parachute/messages.h b/libraries/AP_Parachute/messages.h new file mode 100644 index 0000000000..dcf5f3e38a --- /dev/null +++ b/libraries/AP_Parachute/messages.h @@ -0,0 +1,88 @@ +#ifndef __MESSAGES_H +#define __MESSAGES_H + +#include + +#ifndef FTS_PACKED +#define FTS_PACKED __attribute__((packed)) +#endif + +#define FTS_DEPLOY_MAGIC 0x5555 + +enum fts_msg_id_t { + FTS_MSGID_UNKNOWN=0, + FTS_MSGID_STATUS=1, + FTS_MSGID_DEPLOY=2, + FTS_MSGID_WDRST=3, + FTS_MSGID_POWER_OFF=4, + FTS_MSGID_ARM_CMD=5, + FTS_MSGID_DISARM_CMD=6, + FTS_MSGID_VERSION=7, + FTS_MSGID_STATUS2=8 +}; + +enum fts_state_t { + FTS_INIT=0, + FTS_POWER_OFF=1, + FTS_DISARMED_MASTER_NOT_PRESENT=2, + FTS_DISARMED_MASTER_PRESENT=3, + FTS_ARMED=4, + FTS_DEPLOYED=5 +}; + +enum fts_state_reason_t { + FTS_REASON_INIT=0, + FTS_REASON_COMMANDED=1, + FTS_REASON_WATCHDOG_EXPIRE=2, + FTS_REASON_BUTTON_PRESS=3 +}; + +enum fuse_fault_state_t { + FTS_FUSE_STATE_UNKNOWN=0, + FTS_FUSE_STATE_PASS=1, + FTS_FUSE_STATE_FAIL=2 +}; + +struct fts_msg_status_s { + uint8_t msgid; + uint8_t state; + uint8_t state_reason; + uint16_t batt_cell_mV[3]; + uint8_t batt_SoC; + int16_t batt_temp_TS1; + int16_t batt_temp_INT; +} FTS_PACKED; + +struct fts_msg_deploy_s { + uint8_t msgid; + uint16_t magic; +} FTS_PACKED; + +struct fts_msg_wdrst_s { + uint8_t msgid; +} FTS_PACKED; + +struct fts_msg_power_off_s { + uint8_t msgid; +} FTS_PACKED; + +struct fts_msg_arm_cmd_s { + uint8_t msgid; +} FTS_PACKED; + +struct fts_msg_disarm_cmd_s { + uint8_t msgid; +} FTS_PACKED; + +struct fts_msg_version_s { + uint8_t msgid; + uint8_t git_hash[7]; +} FTS_PACKED; + +struct fts_msg_status2_s { + uint8_t msgid; + int16_t wdt_min_margin_ms; + uint8_t fuse_fault_state; +} FTS_PACKED; + +#endif diff --git a/libraries/AP_Parachute/protocol.cpp b/libraries/AP_Parachute/protocol.cpp new file mode 100644 index 0000000000..8a1a2cdd93 --- /dev/null +++ b/libraries/AP_Parachute/protocol.cpp @@ -0,0 +1,176 @@ +#include "protocol.h" +#include "slip.h" + +#include + +#define FTS_PROTOCOL_RXBUF_SIZE 32 + +static uint8_t rxbuf[FTS_PROTOCOL_RXBUF_SIZE]; +static uint8_t rxbuf_len = 0; +static uint8_t wait_for_end_byte = 0; + +static uint16_t crc16_ccitt(uint8_t byte, uint16_t crc); + +enum fts_msg_id_t fts_protocol_identify_message(uint8_t msg_len, uint8_t* msg) { + switch (msg[0]) { + case FTS_MSGID_STATUS: + if (msg_len != sizeof(struct fts_msg_status_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_DEPLOY: + if (msg_len != sizeof(struct fts_msg_deploy_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_WDRST: + if (msg_len != sizeof(struct fts_msg_wdrst_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_POWER_OFF: + if (msg_len != sizeof(struct fts_msg_power_off_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_ARM_CMD: + if (msg_len != sizeof(struct fts_msg_arm_cmd_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_DISARM_CMD: + if (msg_len != sizeof(struct fts_msg_disarm_cmd_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_VERSION: + if (msg_len != sizeof(struct fts_msg_version_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + case FTS_MSGID_STATUS2: + if (msg_len != sizeof(struct fts_msg_status2_s)) { + return FTS_MSGID_UNKNOWN; + } + break; + default: + return FTS_MSGID_UNKNOWN; + } + return (enum fts_msg_id_t)msg[0]; +} + + + +// accepts a byte, appends it to rxbuf +// if a full frame has been received, writes the payload to ret_buf. +// if data was written, returns pointer to outbuf in ret_buf +// returns length of valid data written to outbuf +uint8_t fts_protocol_rx_byte(uint8_t byte, uint8_t ret_buf_size, uint8_t* ret_buf) { + uint8_t i; + uint8_t decoded_buf[FTS_PROTOCOL_RXBUF_SIZE-1]; + uint8_t decoded_len; + uint16_t crc16_provided; + uint16_t crc16_computed; + + if (rxbuf_len >= FTS_PROTOCOL_RXBUF_SIZE) { + // no room in rxbuf, clear it and flag the rxbuf as misaligned unless byte received was an end byte + rxbuf_len = 0; + if (byte != SLIP_END) { + wait_for_end_byte = 1; + + } + return 0; + } + + if (wait_for_end_byte) { + wait_for_end_byte = (byte != SLIP_END); + return 0; + } + + rxbuf[rxbuf_len++] = byte; + + if (byte == SLIP_END) { + decoded_len = slip_decode(rxbuf_len, rxbuf, decoded_buf); + rxbuf_len = 0; + + if (decoded_len-3 > ret_buf_size) { + return 0; + } + + if (decoded_len <= 3) { + return 0; + } + + if (decoded_buf[0] != decoded_len-3) { + return 0; + } + + // little-endian + crc16_provided = 0; + crc16_provided |= decoded_buf[decoded_len-1]; + crc16_provided <<= 8; + crc16_provided |= decoded_buf[decoded_len-2]; + + crc16_computed = 0; + for (i=0; i < decoded_len-2; i++) { + crc16_computed = crc16_ccitt(decoded_buf[i], crc16_computed); + } + + if (crc16_provided != crc16_computed) { + return 0; + } + + for (i=0; i < decoded_len-3; i++) { + ret_buf[i] = decoded_buf[i+1]; + } + + return decoded_len-3; + } + + return 0; +} + +// returns 0 on failure, 1 on success +uint8_t fts_protocol_encode_message(uint8_t in_buf_size, uint8_t* in_buf, uint8_t out_buf_size, uint8_t* out_buf) { + uint8_t out_len; + uint8_t i; + uint16_t crc16_val; + out_len = 0; + crc16_val = 0; + + if (!slip_encode_and_append(in_buf_size, &out_len, out_buf, out_buf_size)) { return 0; } + crc16_val = crc16_ccitt(in_buf_size, crc16_val); + + for (i=0; i> 8) & 0xff, &out_len, out_buf, out_buf_size)) { return 0; } + + if (out_len >= out_buf_size) { return 0; } + out_buf[out_len++] = SLIP_END; + + return out_len; +} + +static uint16_t crc16_ccitt(uint8_t byte, uint16_t crc16) +{ + uint8_t i; + crc16 ^= (byte << (16 - 8)); + for (i = 8; i > 0; i--) + { + if (crc16 & 0x8000) + { + crc16 = (crc16 << 1) ^ 0x1021; + } + else + { + crc16 = (crc16 << 1); + } + } + + return crc16; +} diff --git a/libraries/AP_Parachute/protocol.h b/libraries/AP_Parachute/protocol.h new file mode 100644 index 0000000000..011d92fad1 --- /dev/null +++ b/libraries/AP_Parachute/protocol.h @@ -0,0 +1,11 @@ +#ifndef __PROTOCOL_H +#define __PROTOCOL_H + +#include +#include "messages.h" + +uint8_t fts_protocol_rx_byte(uint8_t byte, uint8_t ret_buf_size, uint8_t* ret_buf); +enum fts_msg_id_t fts_protocol_identify_message(uint8_t msg_len, uint8_t* msg); +uint8_t fts_protocol_encode_message(uint8_t in_buf_size, uint8_t* in_buf, uint8_t out_buf_size, uint8_t* out_buf); + +#endif diff --git a/libraries/AP_Parachute/slip.h b/libraries/AP_Parachute/slip.h new file mode 100644 index 0000000000..67190597ea --- /dev/null +++ b/libraries/AP_Parachute/slip.h @@ -0,0 +1,67 @@ +#ifndef __SLIP_H +#define __SLIP_H + +#define SLIP_END 0xC0 +#define SLIP_ESC 0xDB +#define SLIP_ESC_END 0xDC +#define SLIP_ESC_ESC 0xDD + +// appends a SLIP-encoded byte to out_buf and increments *out_buf_len +// returns 0 on failure, 1 on success +static uint8_t slip_encode_and_append(uint8_t byte, uint8_t* out_buf_len, uint8_t *out_buf, uint8_t out_buf_size) { + if (byte == SLIP_END) { + if ((*out_buf_len) > out_buf_size-2) { + return 0; + } + + out_buf[(*out_buf_len)++] = SLIP_ESC; + out_buf[(*out_buf_len)++] = SLIP_ESC_END; + } else if (byte == SLIP_ESC) { + if ((*out_buf_len) > out_buf_size-2) { + return 0; + } + + out_buf[(*out_buf_len)++] = SLIP_ESC; + out_buf[(*out_buf_len)++] = SLIP_ESC_ESC; + } else { + if ((*out_buf_len) > out_buf_size-1) { + return 0; + } + + out_buf[(*out_buf_len)++] = byte; + } + return 1; +} + +// decodes the first SLIP frame in in_buf, writes it to out_buf +// assumes sizeof(out_buf) >= (in_len - 1) +// returns out_buf length or 0 on failure to find a valid frame +static uint8_t slip_decode(uint8_t in_len, uint8_t *in_buf, uint8_t *out_buf) { + uint8_t i; + uint8_t out_len = 0; + uint8_t esc_flag = 0; + + for (i=0; i Date: Thu, 2 Feb 2017 12:05:19 -0800 Subject: [PATCH 038/155] AC_PosControl: add get_vel_error_z --- libraries/AC_AttitudeControl/AC_PosControl.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index cc3899e645..fc489f00b4 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -80,6 +80,9 @@ class AC_PosControl /// leash length will be recalculated void set_max_accel_z(float accel_cmss); + /// get_vel_error_z - returns current vertical speed error in cm/s + float get_vel_error_z() const { return _vel_error.z; } + /// get_max_accel_z - returns current maximum vertical acceleration in cm/s/s float get_max_accel_z() const { return _accel_z_cms; } From ab848b0fb0aa5d09b8df4dad0fccdf5295c85bd4 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 18 Apr 2017 15:17:18 -0700 Subject: [PATCH 039/155] AC_WPNav: fix sudden jump in throttle when switching from modes with vertical velocity feedforward --- libraries/AC_WPNav/AC_WPNav.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 8ff6bba6ae..3ce5a4b5dc 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -195,6 +195,7 @@ bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt) origin = _pos_control.get_pos_target(); } else { // if waypoint controller is not active, set origin to reasonable stopping point (using curr pos and velocity) + _pos_control.set_desired_velocity_z(0); _pos_control.get_stopping_point_xy(origin); _pos_control.get_stopping_point_z(origin); } From bcee86d5cc3298dcee2ab72f4a8e8c817a847cfe Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 4 May 2017 15:26:27 -0700 Subject: [PATCH 040/155] GCS_MAVLink: provide matternet FTS version alongside autopilot version message --- libraries/GCS_MAVLink/GCS_Common.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a54a9a02d4..d467b65c34 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2142,6 +2142,11 @@ void GCS_MAVLINK::send_autopilot_version() const uid, uid2 ); + + + char mttr_fts_text[50]; + snprintf(mttr_fts_text, 50, "MTTR_FTS_VER: %s", copter.parachute.mttr_get_fts_version()); + send_text(MAV_SEVERITY_INFO, mttr_fts_text); } From 3f29e2b810983b866a5f7b68b3fae9e14bbd970f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Mar 2019 14:10:54 +1100 Subject: [PATCH 041/155] GCS_MAVLink: FTS message rebase fixes --- libraries/GCS_MAVLink/GCS_Common.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index d467b65c34..eb38a07da0 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include @@ -2142,11 +2143,6 @@ void GCS_MAVLINK::send_autopilot_version() const uid, uid2 ); - - - char mttr_fts_text[50]; - snprintf(mttr_fts_text, 50, "MTTR_FTS_VER: %s", copter.parachute.mttr_get_fts_version()); - send_text(MAV_SEVERITY_INFO, mttr_fts_text); } @@ -3108,6 +3104,9 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST: handle_send_autopilot_version(msg); + char mttr_fts_text[50]; + snprintf(mttr_fts_text, 50, "MTTR_FTS_VER: %s", AP_Parachute::mttr_get_fts_version()); + send_text(MAV_SEVERITY_INFO, mttr_fts_text); break; case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: @@ -3284,6 +3283,9 @@ void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg) void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t &msg) { send_message(MSG_AUTOPILOT_VERSION); + char mttr_fts_text[50]; + snprintf(mttr_fts_text, 50, "MTTR_FTS_VER: %s", AP_Parachute::mttr_get_fts_version()); + send_text(MAV_SEVERITY_INFO, mttr_fts_text); } void GCS_MAVLINK::send_banner() From 9bc683d11d91ddf19c71d67ec2b4717fa462db37 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Mar 2019 15:21:06 +1100 Subject: [PATCH 042/155] AP_Arming: added arming check type FTS for flight termination system --- libraries/AP_Arming/AP_Arming.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 80396e7239..716c435d1f 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -33,6 +33,7 @@ class AP_Arming { ARMING_CHECK_SYSTEM = (1U << 13), ARMING_CHECK_MISSION = (1U << 14), ARMING_CHECK_RANGEFINDER = (1U << 15), + ARMING_CHECK_FTS = (1U << 16), }; enum class Method { From 342ed7163896cea6f948d1de530ca9c681b3ce22 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 4 Jul 2019 09:26:38 +1000 Subject: [PATCH 043/155] GCS_MAVLink: break out MTTR_FTS_VER string send and ensure it is sent on both capabilities and version request --- libraries/GCS_MAVLink/GCS.h | 2 ++ libraries/GCS_MAVLink/GCS_Common.cpp | 19 +++++++++++++------ 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 65c9387d73..aa9075c9ad 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -368,6 +368,8 @@ class GCS_MAVLINK void handle_send_autopilot_version(const mavlink_message_t &msg); MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet); + void send_matternet_FTS_version(void) const; + virtual void send_banner(); void handle_device_op_read(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index eb38a07da0..53cedede1b 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2143,6 +2143,8 @@ void GCS_MAVLINK::send_autopilot_version() const uid, uid2 ); + + send_matternet_FTS_version(); } @@ -3104,9 +3106,6 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST: handle_send_autopilot_version(msg); - char mttr_fts_text[50]; - snprintf(mttr_fts_text, 50, "MTTR_FTS_VER: %s", AP_Parachute::mttr_get_fts_version()); - send_text(MAV_SEVERITY_INFO, mttr_fts_text); break; case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: @@ -3283,9 +3282,6 @@ void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg) void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t &msg) { send_message(MSG_AUTOPILOT_VERSION); - char mttr_fts_text[50]; - snprintf(mttr_fts_text, 50, "MTTR_FTS_VER: %s", AP_Parachute::mttr_get_fts_version()); - send_text(MAV_SEVERITY_INFO, mttr_fts_text); } void GCS_MAVLINK::send_banner() @@ -3516,6 +3512,17 @@ MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavl return MAV_RESULT_ACCEPTED; } +/* + send Matternet FTS version string + */ +void GCS_MAVLINK::send_matternet_FTS_version(void) const +{ + AP_Parachute *parachute = AP::parachute(); + if (parachute) { + gcs().send_text(MAV_SEVERITY_INFO, "MTTR_FTS_VER: %s", parachute->mttr_get_fts_version()); + } +} + MAV_RESULT GCS_MAVLINK::handle_command_do_send_banner(const mavlink_command_long_t &packet) { From 8bd834f318a74123f03ecd25ad01c14f9fc8801e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 3 Apr 2019 11:38:13 +1100 Subject: [PATCH 044/155] SITL: added SIM_PLAND_OFS vector for position of precision landing target in SITL --- libraries/SITL/SITL.cpp | 1 + libraries/SITL/SITL.h | 2 ++ 2 files changed, 3 insertions(+) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 5e1520fe38..be4e0faa95 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -196,6 +196,7 @@ const AP_Param::GroupInfo SITL::var_info2[] = { AP_SUBGROUPINFO(tonealarm_sim, "TA_", 57, SITL, ToneAlarm), AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1), + AP_GROUPINFO("PLAND_OFS", 61, SITL, precland_offset, 0), AP_GROUPEND diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index d321818c47..21321d2996 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -280,6 +280,8 @@ class SITL { AP_Float hdg; // 0 to 360 } opos; + AP_Vector3f precland_offset; // XYZ offset of precland target from SITL origin + uint16_t irlock_port; void simstate_send(mavlink_channel_t chan); From f1f7282a980695f7b5f0342e791711c5a7a45a2e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Apr 2019 09:11:44 +1100 Subject: [PATCH 045/155] SITL: support FlightAxis for PrecLand --- libraries/SITL/SIM_FlightAxis.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 5881ffaa1b..aa9f8cf0f1 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -369,6 +369,8 @@ void FlightAxis::update(const struct sitl_input &input) { WITH_SEMAPHORE(mutex); + update_external_payload(input); + last_input = input; double dt_seconds = state.m_currentPhysicsTime_SEC - last_time_s; From 9c4a24fd8dfd9eee9504bb8b817045c9b1360c49 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 18 Apr 2019 19:34:30 +1000 Subject: [PATCH 046/155] SITL: added SIM_GPS_DRIFT_S parameter for testing GPS drift in takeoff --- libraries/SITL/SITL.cpp | 2 ++ libraries/SITL/SITL.h | 1 + 2 files changed, 3 insertions(+) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index be4e0faa95..7b8e2b4e50 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -198,6 +198,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = { AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1), AP_GROUPINFO("PLAND_OFS", 61, SITL, precland_offset, 0), + AP_GROUPINFO("GPS_DRIFT_S", 62, SITL, gps_drift_spd, 0), + AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 21321d2996..da952a038f 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -225,6 +225,7 @@ class SITL { AP_Float temp_flight; AP_Float temp_tconst; AP_Float temp_baro_factor; + AP_Float gps_drift_spd; // differential pressure sensor tube order AP_Int8 arspd_signflip; From 7e579253a03e69d5bf8dc96892f534f433d6230d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 18 Apr 2019 19:32:57 +1000 Subject: [PATCH 047/155] HAL_SITL: use SIM_GPS_DRIFT_S drift GPS position to north --- libraries/AP_HAL_SITL/sitl_gps.cpp | 37 +++++++++++++++++++++++------- 1 file changed, 29 insertions(+), 8 deletions(-) diff --git a/libraries/AP_HAL_SITL/sitl_gps.cpp b/libraries/AP_HAL_SITL/sitl_gps.cpp index 8fdb5eb97e..7d53fa5c1d 100644 --- a/libraries/AP_HAL_SITL/sitl_gps.cpp +++ b/libraries/AP_HAL_SITL/sitl_gps.cpp @@ -1301,41 +1301,62 @@ void SITL_State::_update_gps(double latitude, double longitude, float altitude, } void SITL_State::_update_gps_instance(SITL::SITL::GPSType gps_type, const struct gps_data *data, uint8_t instance) { + struct gps_data d2 = *data; + + static uint32_t start_ms; + uint32_t now = AP_HAL::millis(); + if (hal.util->get_soft_armed()) { + if (start_ms == 0) { + start_ms = now; + } + float dt = (now - start_ms) * 0.001; + // drift to N + //d2.speedN += _sitl->gps_drift_spd; + Location loc; + loc.lat = d2.latitude*1.0e7; + loc.lng = d2.longitude*1.0e7; + loc.offset(dt * _sitl->gps_drift_spd, 0); + d2.latitude = loc.lat * 1.0e-7; + d2.longitude = loc.lng * 1.0e-7; + } else { + start_ms = 0; + } + switch (gps_type) { case SITL::SITL::GPS_TYPE_NONE: // no GPS attached break; case SITL::SITL::GPS_TYPE_UBLOX: - _update_gps_ubx(data, instance); + _update_gps_ubx(&d2, instance); break; case SITL::SITL::GPS_TYPE_MTK: - _update_gps_mtk(data, instance); + _update_gps_mtk(&d2, instance); break; case SITL::SITL::GPS_TYPE_MTK16: - _update_gps_mtk16(data, instance); + _update_gps_mtk16(&d2, instance); break; case SITL::SITL::GPS_TYPE_MTK19: - _update_gps_mtk19(data, instance); + _update_gps_mtk19(&d2, instance); break; case SITL::SITL::GPS_TYPE_NMEA: - _update_gps_nmea(data, instance); + _update_gps_nmea(&d2, instance); break; case SITL::SITL::GPS_TYPE_SBP: - _update_gps_sbp(data, instance); + _update_gps_sbp(&d2, instance); break; case SITL::SITL::GPS_TYPE_SBP2: - _update_gps_sbp2(data, instance); + _update_gps_sbp2(&d2, instance); break; case SITL::SITL::GPS_TYPE_NOVA: - _update_gps_nova(data, instance); + _update_gps_nova(&d2, instance); break; case SITL::SITL::GPS_TYPE_FILE: From d0b04ae1d21d73848048118cddf104adcff814fa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 19 Apr 2019 10:03:35 +1000 Subject: [PATCH 048/155] Tools: add a useful SITL test script --- Tools/scripts/runcoptertest.py | 58 ++++++++++++++++++++++++++++++++++ 1 file changed, 58 insertions(+) create mode 100755 Tools/scripts/runcoptertest.py diff --git a/Tools/scripts/runcoptertest.py b/Tools/scripts/runcoptertest.py new file mode 100755 index 0000000000..4aff7d384a --- /dev/null +++ b/Tools/scripts/runcoptertest.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python + +import pexpect, time, sys +from pymavlink import mavutil + +def wait_heartbeat(mav, timeout=10): + '''wait for a heartbeat''' + start_time = time.time() + while time.time() < start_time+timeout: + if mav.recv_match(type='HEARTBEAT', blocking=True, timeout=0.5) is not None: + return + failure("Failed to get heartbeat") + +def wait_mode(mav, modes, timeout=10): + '''wait for one of a set of flight modes''' + start_time = time.time() + last_mode = None + while time.time() < start_time+timeout: + wait_heartbeat(mav, timeout=10) + if mav.flightmode != last_mode: + print("Flightmode %s" % mav.flightmode) + last_mode = mav.flightmode + if mav.flightmode in modes: + return + print("Failed to get mode from %s" % modes) + sys.exit(1) + +def wait_time(mav, simtime): + '''wait for simulation time to pass''' + imu = mav.recv_match(type='RAW_IMU', blocking=True) + t1 = imu.time_usec*1.0e-6 + while True: + imu = mav.recv_match(type='RAW_IMU', blocking=True) + t2 = imu.time_usec*1.0e-6 + if t2 - t1 > simtime: + break + +cmd = '../Tools/autotest/sim_vehicle.py -j4 -D' +mavproxy = pexpect.spawn(cmd, logfile=sys.stdout, timeout=30) +mavproxy.expect("Ready to FLY") + +mav = mavutil.mavlink_connection('127.0.0.1:14550') + +wait_time(mav, 2) +mavproxy.send('mode GUIDED\n') +wait_mode(mav, ['GUIDED']) +mavproxy.expect('is using GPS') +mavproxy.expect('is using GPS') +mavproxy.send('arm throttle\n') +mavproxy.expect('ARMED') +mavproxy.send('mode AUTO\n') +wait_mode(mav, ['AUTO']) +wait_time(mav, 30) +mavproxy.send('long MISSION_START\n') +mavproxy.send('module load console\n') +#mavproxy.send('module load map\n') +mavproxy.logfile = None +mavproxy.interact() From 0a854d46b515c8616fa5c3deee19e4abd7aa322d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 8 May 2019 09:38:30 +1000 Subject: [PATCH 049/155] AP_Arming: allow for disabling RC arming checks on some modes --- libraries/AP_Arming/AP_Arming.cpp | 2 +- libraries/AP_Arming/AP_Arming.h | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 713e156f31..a80ccc5d5c 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -544,7 +544,7 @@ bool AP_Arming::manual_transmitter_checks(bool report) if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) { - if (AP_Notify::flags.failsafe_radio) { + if (AP_Notify::flags.failsafe_radio && !rc_check_disabled) { check_failed(ARMING_CHECK_RC, report, "Radio failsafe on"); return false; } diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 716c435d1f..8ffc7959b9 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -72,6 +72,11 @@ class AP_Arming { // get expected magnetic field strength uint16_t compass_magfield_expected() const; + // allow RC check to be disabled for some modes + void disable_RC_check(bool disable) { + rc_check_disabled = disable; + } + // rudder arming support enum class RudderArming { IS_DISABLED = 0, // DISABLED leaks in from vehicle defines.h @@ -96,6 +101,7 @@ class AP_Arming { bool armed; uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]; uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]; + bool rc_check_disabled; virtual bool barometer_checks(bool report); From adb98a26c4866e0aa7acff9f02ff5414d16edf37 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 7 Jun 2019 17:55:30 +1000 Subject: [PATCH 050/155] Tools: updated runcoptertest.py --- Tools/scripts/runcoptertest.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Tools/scripts/runcoptertest.py b/Tools/scripts/runcoptertest.py index 4aff7d384a..774b276296 100755 --- a/Tools/scripts/runcoptertest.py +++ b/Tools/scripts/runcoptertest.py @@ -35,7 +35,7 @@ def wait_time(mav, simtime): if t2 - t1 > simtime: break -cmd = '../Tools/autotest/sim_vehicle.py -j4 -D' +cmd = '../../Tools/autotest/sim_vehicle.py -D -S10' mavproxy = pexpect.spawn(cmd, logfile=sys.stdout, timeout=30) mavproxy.expect("Ready to FLY") @@ -43,6 +43,7 @@ def wait_time(mav, simtime): wait_time(mav, 2) mavproxy.send('mode GUIDED\n') +mavproxy.send('param set SIM_SPEEDUP 5\n') wait_mode(mav, ['GUIDED']) mavproxy.expect('is using GPS') mavproxy.expect('is using GPS') @@ -50,9 +51,9 @@ def wait_time(mav, simtime): mavproxy.expect('ARMED') mavproxy.send('mode AUTO\n') wait_mode(mav, ['AUTO']) -wait_time(mav, 30) +wait_time(mav, 15) mavproxy.send('long MISSION_START\n') mavproxy.send('module load console\n') -#mavproxy.send('module load map\n') +mavproxy.send('module load map\n') mavproxy.logfile = None mavproxy.interact() From 415894f861aef9eae1a7c01855b99cd15e170b6e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jul 2019 14:14:43 +1000 Subject: [PATCH 051/155] Tools: added bootloader for MttrCubeBlack --- Tools/bootloaders/MttrCubeBlack_bl.bin | Bin 0 -> 16056 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 Tools/bootloaders/MttrCubeBlack_bl.bin diff --git a/Tools/bootloaders/MttrCubeBlack_bl.bin b/Tools/bootloaders/MttrCubeBlack_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..6f6fc3ecff453fb9cd8d06e65a51eee7c89d9db9 GIT binary patch literal 16056 zcmb_@3w%`7wf8=cNhS}HNhZKB2{4&SFc8pz1Py{RnVFnCCK@DMF9fY;GGNaH0wdBE z+ukxESP^>L*r26BTQu5=4FFLLe@;ijvKPkO0Q4+dZ_r1{7&EKOn$FIn!*);(>SyLwy z^6uXZskeW!Y@$t)C3rPw7j4DL&kS?&&xY#cf3eT5&aHXGxhzz!@M*)*yy_X(-b#Bu?1^xClCFLK?2j|{tiuB3-gN>2#Ae>Lpx z{ZRfMv9(^!+EpYRs3aCf?igp}nsM^Zcr?&$sZFtwLR(<7ygX^PZGGUGz@hnAOXrqLTZlYm%+i%5(5QdWL)Xi686Ur~r07$b7gs6_y-AtJx1VDtqaMR}n=O2@;H*h{*IO>fmVwIEI8+}9aP zppt~DfN#NHlsa4OUX<&EUBYx>&#~);ca(3oksHdwC_V7n0Lj!vELJtYN|@6~O{uj>#x9%0EVYR~qTS<>kvh}bQBJUVoWb=uJ zUJ@z=-h({RZ<|Xj0j-ZhPhoYv!r#CwA`wIH9;Xtq*4jK)sl$2mS*vHi#0?N1HyCtv zI2WD5+>*aKGSkCaOaUU_Hk#)#ZzNXpx*40y_s-a~W@E#;HJcjlZP?V{cgjJw!Q0@s zPQ+%Ekd2A)N==5xDCSC5$&%lKkvt)^VznA7DV?Lsi9XLk^gM!!G?hE0 zmz1#%{YT^iK{=hjM{0j?#A0m`)clNReCjX?E6-e+f!NJ$Y zi0!8}&rEReYsgU!_CUUD_$kjxg|t2CIZ#6i@&c>GLg6}LpTJ$P_icWZVa8mdCz&n9N@u zyZ`WH?~6wkftuHbjtr30<5wPNG0U9JA%CR>Jy??ZQ@M60xw5I{wZY(aa;2%o?P1#g zrDDpt1Q&li#I~^=WZv;BcegP6*^bMrn8kmK{t9Cq9!re%j+WWiXPx=QfQ4UGQ50Gw zWIR7d=7?2TRBdt-Ic>y>IdVf4k?kXOm!C_$XL$FO;%d8~#>qGjUbTdi`gbSkgnd!U zzwj6-S{|ErSdG7{rLqna>-RNIbU4?XnmupUnT-8RNp9FGbKJCpY3_Q(vMiJHI)lG>k) zd9wVIDy{d?Q7R|rp?NZw`kMQ-isiAMLuHtcbB6eQeVZQZ@MDF)>58@z)%Yb1y7-V9 z|3phYe27XhJ*>B893&Y1h*tWoLsZjepl$B38b3X1uVUm`BS{}z%d<9xuH)@7okm5E z)=qsP5Oj ze>BAI&tIBdy!?}2zQ{baQnAUNB%=2t{3pVKYr^_uqVG&0`q_G-=MXPO@F7r`Z%o8j z5#IqgT6R+^(I5CWLl*qyY9)J!6ks)dB}rj!%c*-uSsko!{a}dL8}jZM-Z{jCJDu5) z)k*>3B*uDLu^d<^6bs=>rYJd*>Uly*CautqEY*7tF{S+ccO!MN;Q%AI4cE!4{YsRC z=q|nw`%2MLO*dE4z7qW;3AedO!RPxjO!UQH(-&W)i==pHKXfll^mB2dpS!evXz8{6 z*k4Zen71W+>J_WQCjH5;^P~zd2#jD6?5~U1-zVvzJP33%a?5B+ZOZMI04cOfwr#CW z{aHr7Z?r_xxtWsg!C+m9c;$2e`_B(CjvxXfn|sLs5y@cCK_plVNPnNu93wyTIw3lb zS<+#z-EVGnvS$r$*h;Tsr>dlFDUP!4BVG{UZ22|mg}M>WcDK|%q_;S)Fx=zLg7C|O!Fz1saxIsSm_zAo z#L0;Dp@mlWtaLYXOPbK>oONpI5VLu8-eX;yKon-PAlL!V3Y@UdY#d^8$=u;cpptcS zLc5aH1o}P43fn~0iFDo2*-2#2v9jLDwKIu} zm0VJmixIglQzgbi*qYOlOFqt>7Ljuk$LI1@U&wDG4%lnuVdbuMaj8T)r_%|KADz;d zu+HjY85fgSvQBAxRMC9)yk5l_T?uTC)()-$_SC`he?re zPM=>iQ;ol<)_t=5{-utq6F9z}l+ou)N}qtgys@~s!^uX9Hoe0sBtMvcA-O74j$QRBEp{+I8pne7Ibb_{Red_?eo5E&s3PVR z2{XXA-r-W|>7zf12E;d_*U66L<-7rOEl*eDBL3fsqK6iJH&>;`x2e4!>Y)c3jy(=J zCCWBUl&v_%Uq4y4ZlX*$ws8?X6J*q8)W8PB&i${$Q#@}fca^5sPMIjVeK<`kNvln( zA^Fr&tQbz!N~ldu`>D>vxe&6V_}9=ht1pj_f0a_6q+J1#k_D_S+~j% zS?t;8bVf>H?K@*+k$IhYlNR5byD2Sy4)(7m<$BNC%3TE=&SHrT&#&I?^hD-YGyU~U z*T~hY2Y2atXUHZe6HZR%T$deOyV$?WB|EtNM~&X%hg~v*RK2%6#@D;#`It{k?7$tw zW)!;ygPV;~y_6o>Zc}YL6|uCecRFZEk7Q}I1abDDv>?`Kxz6%x)PVY*VHW|da?q*O z(^#utX?Zr9QhhW^LaVVZC_m_Vf*2SF$wBC4bd)cYAHhEdSu!BHh&-Ehq;P{?R|*p( zzdnjG2lgi;8T2|BTf5`95?sh({wv*6g&k6o|2b!x(Bdx(Jt%$E-0kFr z$2$GR?oRKN3t49u2_}@B7(1MMv+%BDcf)QNdr!LA{gk&;TASM`76}UUCT(?O?4tC3 zv{j-jhlfs?D$LPvJN!2Sd!~?dib6dx<^ygYaAyPeGyO?=HQqkv6nbV{kkt5hf!pbB z{1i8xfwa{Q4Y#2?)lCXcdSQ)-4soaWbFsx+?q$7PqoG&dy~FSFw>z204rxcv4vAT` zLu|-%dS?Wje$Llx{pu1@JGKeMz` ztk3K8PTgh&#)8mAsndJWpVnm&_CdE($RZ)oyAb+^$oJz!_1?J$Q5NW3@RxXiFBXQbr_>$06L4L)`jJ4UeCL~Sw?XvEZeqNX&q=L-Bl z4%&A>4oT-MGhrim>Hen19}JcCesSE!Zuf?_mA$2ADQg=)cWNa6o9x`|$czWFA7*TO z97bpz<{&>%OBngaalpBm{rL~Df<+?oxgqw5p*IJXe-G$L@QsmQLb?`Zd)`Qt(e#5z zQ@Do`aNrwk(h0bKO~5UpaCaabR`wQ@bsMD_phhP!Va8I{%YdfgNcIDFJ&3H0uTOa`VA{S1UO$zt7s z*`N9V*S~{p^VU3&vdE=a$?gZTyHLXI^RhN>>v3goPC{msma=YcJ1-c!+LTrH=X)$O znL;*SjW1HE+zP+8S!Ng_KQy{iS+#=pO7jW(T5>DSDi ztOyyX)fEYh{JXK$UCcq6GLC(I7X3`2vmEQCzlDo;KknB-`^35u+DF&_?PSYLJ*a2 zy-x2AFC+iqRrzJ$<0~J2Ut$WM_W!%%7FR`!4Z7zk(I?8UGx7l1Ct#8_m~|SA?sG63 zdgxxp!s8816*!>Ot_Ui(Bh;U$c3s6~uF!FXEqTI8g~rsvtVb6e-?RJ zskPf=mU|lUPkbNv=BzszbzEV5PdI0t=^i}3dFiR{!2_E+0q3^Agj9ysa;I{;o!SK+ zjmO3=Mx&p@+#$A3-$kEo-GONLpkec(u;UZf^@MXJdL^5K5q_YK>+~_Uf(y_BNU^qy zzQT38qX}xZ#{!2bJucAm3d*W2UTLpVWxoyIN(1GBMF6Db*-GkTYB=nYI(?jU(f4%J zwv8_~L=x+gj{Vp;wIh7ePNfdsY%V_^a;03Q{gC1p!YH@%pq6r<6h9qiHTn-kZ}KE) zBDN>cf0ZFi4rWq$WilCIBJWa}qNFejFH_#(>j8Pe_vPpU#Fu>VuF4zKkF{}-;_b2Y z!<23#+EJgYImsfheT@9x(B>#3_YH0Q6izwx8C>Jx+zGhXhSmb^#i7;FoKNLi4C|B5 zWHr8aJYk33-8J>o+Rvn3JI+PZJ}v*O)ynaUu(997-taoYafGsNI>UKkYVq7N?|jI~ zw-(VqeADJG(ULTGYn$RRv?(=~lN+3u8Ec0#=j;h7d-qEtR|eUUsf(L?5^p8yV_{(~^ja(PCHKS3I&&bP%5^G}N(C630nJ6Kk)G~Em z8CIk947KqcpOiNmoiiiGSa51)WIsE-FHKvcpQq-`SVEJXgyvi;757Z`M^_m6|T!7j6P2lXsTKa?JEj+|Z{o zAMPO`+LnipE!W=$J-E-g7v3+r`_ghlw;p$27Qb1timOD%YV(@6s_`}zUJRV%4UX~n zcQu-Kh^&>}O03SU*tMn3fp4-dC4D~YcPY!}JMk@>pIqZo^5&nAT#8{nYvmOEe1dQC z{LTRr2~_5D3A>Z>SB?K!C9pcw_`V5^M{RW~zg+)nZ>9x@e2wOWbkz7&*j@T=P^3vq zkNPi7wA1%icO`k87@0|I5RIZswPX|T5-T9E^s<&k6CaCbP#Zuya=` zIro%>*!)MGNy2O)HL}{f&zsk%6D!0PQ9lEBk=SQ{&|_+PUMeuB&tOl#Z(bnr7an)A zr>HlxW9WJ5acAtz2I+oru{cZIB)%*jl<2%m$vr5JcyZ!MCk{Ql2eyLqHj=4_xmEb63G&d>CAuw~3s!W(i zfl6Ifppu){5#p;z{|W7!@;dxv0R%m4I=Ub0ah@2DXN>>iC^T~^w=J#5gmda5Xvgt* zKTcX#BbbelKfQ}=5%wR^3+ci%)D4a;t9}b@)c7A&eHXj@+0!D$b~Rkq43DF60Yk*a=cc%Yf@Y#*QC#<*g+Te^^CI0-WuB?0f8u zGlX+T+nh-QY|_nVa>hiyC#UMUJcGi_HhStVXU(F!&nzYNLY9(hU={YS`<$%8jQVg4b)qFiETg z_@k&_(EuLn=1#+&z{u04a?_^GOstfQ8fvM>hAqOB8hRr5csL!cvnN^`dJ|B|DEsqJ zESktsuiD_yN6}wlzxgWy#ZPq({A1O)pC8Z@HD0Xh27bfx0|t^(t;P#f-QaJw@L1(Z z)d^jc8zP}UE`>J(@^^#wI}qrY=qnKF-#pKazD?H?S%!P)?i6_b@9$CLvWi;>KbaQ_ zCDk;D?7*%?4I;EsEZArk^}RRW3VjZE8}sD~J$$ga+uG6Q4=Q|A^j6%7TX6|Ktd-_O z8!blub8V*=1-gxA(rVIbjoW-ZX}4qLc-^?+yHl~PU`kBIbKUU>V>1R;DHekHNatke zarC?ZdKb6O9BvTS&Jq{I;0mew)|kU+S`X@djr@l1L@1#xqq;`jPW5*wZFk&r`Mc7_E~nT$lC0 z+9TYguuDsViB_@k8+Y|6#Qw_Bmz=MMFMwB?KatLjYDjupQCB@A-9OIQ(gONkTNm~C z>H}(g^bPpQLUdkC%4J0nain_8o3r`kx6Pa3UEN~-vKBkdU)I$aCGhcnqezZ&9+zS< zU$nyUBYYEiKTS%yXeKIya^LB)w1X(ci{c%>hzy;iww_rCNbI1Ey3zKaRbF zgth|DanNxP`=PeNujFXB1L7#$jF4744w7;FIlNsZiN?w`0_hE+m z`QiKX?@txc(pu?Ou6GNxyJ+^PiO*i;#CpA;)$7NjK{H9i}@ZZ$;Ya zKBcq>cG56jiCiY+Eu~a%!bw$r=nci-c%h%+I`LY_CY(`B)lVONsefmt;mlrXw(#@- zpRz{b5C1|T2k-*tEWbP+&2y)@_rmTv1>XY206QA;Fm&r`=?d~Fb@Bn1Z$0bjTu;{y ztrKs-UGO%hIM9vrb7Y>!-Mr748=32A*Z>bW+u&oC-_rAly*9g9XZ6o5erL}*^lcH zlx}x3-gMxUq{bJk2b+lvGRpoQ@RgQ9@7)W$MG4uuvYC<}J5MOYkFencWQ&k?^DWJA(Ogv#@G@VJmNTWs7%N7@PPy8(+}(U zxC{BEddiWdNcj;j>2Kx+3@lcn@$&l4Mx}Qd`0fZ2gR{9!x!r&{p<#AiW{jYwEKo_k z_8CV>|F`v1Ao+Adrj(4EUbc8em_xXw=9W69*c6&BxSQ)PSIpx3Gw@sm^RjriUpHV# zC-WTPn%%mA)!bUjrI?b-MqE67Y)zc?3N|x&dz$*&WT<(uwtIJRd&K)eBwC)y&$} z&?yc+jPLB65MyDnV-ZsI-_*g|!~9m7(Uc|`MGww76rOsN?A?Eop7R@})8dRCNAb>( z1Gh>WcIQaW<~%pE?B$WGF`tVou~E77m*dp`rVBTkuH%q>vBaU2DNZ?>5jmyk%V<4L zfZM~E5ji239K>A}sXvY!YO*2yr7oFwLGnxO345@-;I>W8N&OBZFPv8N-+;FHMp<%d z-ybl?W+W%|>H2qa`NDarNLVZFs~k?gL902RT&&fcm44T=$6vMkOVTSN@)a_Y-MG8Q zB%PDmoKsF^n_EB3AqoAPR+SIA?pAj~7gM=W+3;63JZ!tnavNHH3y)O3z*eCK_nNd` zTXWz`0DN&ZZ}iWRJ`ih|JCB*&@WES7D29}I5-W2oGcOh62HkqD- zJn~7*arsThFQW90WmZ*1v##Hbd8YS+Oa6i6>3w}zjpve$eFR)OD|!60G4>xgO{Y%f zlIzUkJz`??bnN@ohcNb%B-)1R;7)kzv%>TYsldjV-J9SDr*VX9*#i&Ehv9s9XD&r? zLeX^4V^#D8XhriT|MUJ?j%l&rJ)69+O2gxL8wMh=x z#MRX4tenZQF**C_VDJVaKN&na=(r&@Lf0ZQ7`)@WWNM-wkRLl8XlLj86jPP4?_G}V zqqf1(@u!etka}_4hZKGH_3Zd{NO4GYj(>&Q*>@p10c%&EM2f-|tBpue*g2{#dHdk~ zhbgp0-4snwY`TWxdxjqxSzGag)B1i7)g5!$n8QjbwPHSzxn$m~b2N6!ZB(PoO_YtC zUn7XkxN91CWim$@);Llw7X7E)QR;YYZ_lU{y5=Og(#?dJ05qSMR5x6U^@8(SKG-stjCT|}(qP32z3dqUjNc%qTs zp^V4>1iu7_`$)WfiJXv9yXa}yG!v&`{|xa2Z2uGD3BS?3!_Rr?ZLO<`^OF4W_$#n0 z=?&XOX=zuZ-#9Z{>TEQ+FE-+w)oc5DNe|rt#&Pe4o2YYTz37SH^$$5IoxuI?NztWY zbWLD%d0|gBavKt_NdmAZ6Zd-GZn_mV^KVrh?f|G?mEH??HoezmRG77$jd)jcn(kzM z6JC^$fuF8kdQ;mb{7|r5N3{Vdd`@^aY>B`OI9U2NpW2v@IENygO^y=Bjh&5-#ZRFH-i~O!Kc?;m zrizL)r)Y1#j@pF=VJv=jtg~sY`%CW5#=G6{G7>{KtI3HQ;qy;wqdnQkL0Y^ft2Z@S zwP><(`C!Wtw&{fEY@!k**3TrR54rp-?v1aJldwYJm!@fZoW|Rdf52Nv>mBT;pUKPS zH_v>k@jb}ki}E^#+tF*~H8BTn{s(j58i|q5-Sa=#w74e=a`~ld=t_8uJDX+&sN9&6 zc4ucJfBId&Mc|jvvnF0wfNS(_pUQ2D@Cfeqal@eBg;Fx-CE=${b-2r?Qa%8gQ4ZTR znH^|~HXZCw;+C6#3~PF};J6|8tZu-;{fojEI}o0jkQbzNV?tV=_4=qvWq*6c*;BNa z{}Y`n+zg2kNNlP57D((?H(sscwFBkzNhz0ldEhG^iMBS8VkOKk-ESTY8^x1&TYpkK z={LJu{j8VX{c9@&Tw!dN;FT}!;o!$z?K68>>p3c)5cNedDARIUdbMw|oStzE-P3Ea zSB#Cvt>eK7ugp)!7@J!$rE^=eJ=ry9rTo|hZwjB1p6W7GpA&y0!J6Ol8!@9g6)A>I z6%E#NU$af79-%)~X z>;1TIO@?i)KMOCwoTlfbALTygoOv2jNqtVTHT5a!M~rS;W3hD1d5`#$em2SHeM?CX zGWb11n@Txa966)$2Q+#lm$*l26@M$86yZtmdi-4D9>1$G4Zd)|z^`ic zSgXu_#}zdz)usKmAf|4yf+sX>-heWnxf$Q}_|*;0gVg6@s$vK77&RVIrz2H{)bG@( zNUcKZmue1D0i;f-*+_i{sa`b;sb`UTRn0`|O{88@GmyG~)FJI{7LlKRRXdLp*0GoJ znr9t&mFOVp2nK{41QS9Yf(5<-{B}hhQsWG~A;k*y35>^|$6D3K1fS6Nli}I!!>+D^wQ?+D%`c@nv`z;3=vXiM+aJ(x0)&1OEYVEUc-EIm)x(5ugNqd8t@`6=xkWmKwqIb8}41ZDNqUMEzti7{=!FNTIEP4dv}#l zUT3XK_yXyAEI*N1uCLK|*ZZ@iGzUk$EnZs}_4dGC!I>a2Giu-;V;p7haa;?_PQbPU zHvB1U=|68ET9h(00SV%6#O~Yub?uBln(;?@OsMZbaS2eU+Wa z>1x`M3nQ1%Y@s*6-wD2$uj%KT&IWHI;HT9Xo6)*?U!@H>^om>9|1Uu_l|R{YAOF9{Yq#UZ>crt^RkvJ|EmuZxSxJX)4*$TntY5mLYEwvt7{^5x6X zl(Cdxb17#SLj%JZ)-cJ2g$#-beS=NwjXZ1v_{eE`2GY)nbUxCx6KU!{r*9-D-$W+x zm)f^Y^i;a&(^Tn=t5*~9813Qj|8ALzdjN#>2zMadjZlrS7$G0wJ_Oq8D|kcXMR)?? zVT4B!S`eBM)*uWaP&jQMh*_G!-;*YyPniK<46c1%fbSl6&X&nKE&)PrLp@Cz5PpYx znx4c%&%_MFl0s))`AT;oDXgzpSzTURNL*iOT<_fI^=%;bg^Nl`7vFeO*^+Xn%UvOm zs`cA$Sg~dEy?)p2uFv2WIBS9T-)*2ZpXjH6uKSR7p==v`=qap=unalACVN=mCS;w#r8nw`fWFx!@T-l5P6cfjx1&jem zSq_8YIUuG$*9L8rlpFs=xE7YC|6lNcc+^bvUzrKn;ZE0q&I*) zU2yJh+Lc!4m|B7D7MVaG`D+2hL9l Date: Thu, 8 Aug 2019 09:15:19 +1000 Subject: [PATCH 052/155] Tools: update MttrCubeBlack bootloader to not listen on any port but telem1 this disables bootloading from telem2 and GPS ports --- Tools/bootloaders/MttrCubeBlack_bl.bin | Bin 16056 -> 16088 bytes Tools/bootloaders/MttrCubeBlack_bl.elf | Bin 0 -> 486836 bytes Tools/bootloaders/MttrCubeBlack_bl.hex | 1008 ++++++++++++++++++++++++ 3 files changed, 1008 insertions(+) create mode 100755 Tools/bootloaders/MttrCubeBlack_bl.elf create mode 100644 Tools/bootloaders/MttrCubeBlack_bl.hex diff --git a/Tools/bootloaders/MttrCubeBlack_bl.bin b/Tools/bootloaders/MttrCubeBlack_bl.bin index 6f6fc3ecff453fb9cd8d06e65a51eee7c89d9db9..7a1c2d1102fce6de640cb84a20d2e80075c3dd8b 100755 GIT binary patch delta 2736 zcmYLL4^R_V8h>xIAsa$2K|~S=x*<}6{E`3v!6bx842qTWl(SSgSY! z&`BOs`SN1{%-Kn%tXT1vY1%QmmqcWGXU*9K@cNi`jCCY4bfp44QJz4Yl{ALljir)D zhbpILJed3aOeGgg`|lVUl$LcO5wR7dPUQlRZx=j%Hs|3V=U(~I) ze3)yWRaPk1u^tqk<~Fq*vN3ls*F?g@V(}8PGE5)!)@6j`u4uR171MSq`jCyfqqSqs zLAHkJHP%^kzuC>&{o{ES%xxgAgiXi|5PO#FRaa3=A^Ds7gME3vh>D1{tOIcwvxyFg z{(LsYtu23{iR>^WMAg7R7nbI(U{ zL6o`e@}_9&aAM1V6oT=|%7gr`g8p#^a&ZsPsZVv=7Ie>(54C0bVhxmm9a$v%T8S@5 zmYo@hts#-&kMJHMU(}pCB=$5W*?a2LBjI;496Cpk|4h6PQ{WhNr`d!2pT%$71@^b= zdfZ!LdTPxM!LM_y0G|)Y`-|dn4;fk%p*ktr9R2zccaT3u9xaN(N4$!NixfUW`Xf8) z*9C3~$L#o&aWCay-H7{Yn(Ed17pGxv$d3>dMW)1m0el6}o{#5s5`PAG$@b>FU%JGf zT<~k2_sfv{8p+uuD{(rxy<`&}B`HyQ&ATGq>+$!(;r??8V$@_~)N$48v-D&Iihoh^ ze;n1J`cB+@5uYF2G6wnTnRJI44$K3m(fAQUR0qXjiaKDMqqYMmj;gcO9jwFL zL-MWONGbbCNOT-NL=vNuAl%02P56CsKDtynI)jYTD*jHUqX%(4>5rMf-Q*oZEcjkE z7!@CyU9m*DX?i}2lc<;O2#sBkG}GkZ(o6Uu z$z4_qP2ajK6Z^=yWmbI5`yUwb1(IUa<36(5*o0e&&lr#0mKBCxK7;N)21k;c*=@d1R(~4>D0%ddF9Noi=)sqVaGvoX5YP zqXjCN7O(+lPL3hO_}ID4l}h;mX*Z?pYk9&t)N3f%(55G0pzWNQ-+rxs-ctd(=VqqH zetd8D%*5DtkT(PClX@-B7q&L6LhW4PpeGp=TYLU_zf!ss(fxo5_6{p;!~4{6meE4tN@=OZtlM;pfpqMU4c%kuRSF& zX{HuMwlZsEjEQs3`LJSlzsB{pAws~*l*+2I>ot@>8T4(K(_m_nq9j>ncr>KTVzRG} zJ>$XIIP1#Tt%ZdDRfIwr%}c>$F@Sp{efgkT0278QibbB)0uh&IV!@jpzXk8p`Y3yd zi_ZTN&KC`7{dNQDliaKVtr_W?8e4Bh7OgAIXJ}qdD{dK@?NexvVf!4l8@8(|OzzUD z{ku)IlwJA%C~0$1o)ze=r2@NNiUOaCJj#MR$Rfp4_;4IPhu9$hi7kjv$a-r8`ia6v zox^c3ty(f%3(jj1lDT5sr;u%sa^bjWk7xBB2y~_dvDl?+gH9eiLyQTVu#D_Ys8Zj8 zPi3bSv2!4I68>TA22ZU|ULoB8nL;JkU0UBjxq2G3el#fAenW=LR@_1&5?i4;I}!)+ zX0LOFm%`m%F`Iz4w1k8B*ds-MSch<1M~(^CD7|YLxEle8U^$UP%|q{ zDDndXQfCMGvH;@Lg2-2kB3~91c|AEm3Tey&oA&s z;N1(n)YYdGNlszGzVt}M!~&`TWq@Y^#ehUWB%lERkx(OC`WpdVfObF!pcPODSPPf{ zNPbuv;GyOTI<7;E2(Tav`V(9VmjO?0GK9#ZLV1l4-uWxorB|QEk!k~D3Y9ms ztz6&I{L9ADb)~4Z^%o7coptp)Qf%<~sVdvxv{u9;^t(7%hY|V<=4%AL6ykVDYmp0I zCRd7LLgHv4dN+m)NBjm;KYUV3be z7IO?IZxr#4L7OM=yWFg%4qKiXd>7p5K1I1-c){tR&Y55O`?_<^ZKiXzNu21>b1T56hrG8WA@{UY55D!_y99i@e+Z)e0+H<8fMML} z7mk6iz4ZD2`@-3_%f2tWA1}E~;U;o%Sx0@2@0NI?6nC*NQXJz%{GB&7IZQ{0$d(Dx?quLcf%@T*l{%9ps{E3cp6W zqGP~zAes&SZmwk#^S8+a@K5Hp0l!GpG1cm85YrXFRnibc)NAGzX2~Epc2|gMu_uV+ zSFs=A`y_dJA-+x;ms{~Aa(a0&KIXm$Eq;rztO376RLG)l71Y7f5g-SdH37?=>$#M zaBy4Th zsQOR6E*A3|94m&5>%;Tw>nKQ@N8T{dF7YlTnbxyl z84S8_=Vm5<@|&HTn*0n-{oyL|ZCqq_vR^g*Ii;M|B6Wpdi1({zKi{LA)}x>bxup07 z(-0aOTLl#Z4zd)sunE8rOZ-sy7%&Wlh(WHkV`MhoipSiRgl+iX6XnJvR21Scwk%Nw z-!it?XV4zw&VaNVcdFJ!I7?;@?Tx5Ky$VN($Y|kG*r+1pLPfG4cIcg;847R?F@E9B zkgZScFgd$W*lpTDug7sl7m6S6^$VZ+%bT1NC0l-A9@m=8*A73LEEkn4#-Mqq0;cIR-Rf9p7u`-52KC*FTdYI0atDvtHF8$tT45 z4lO3x2jqHIh3S3Id=6ro3ZXzxp>d?}s(4vy(fB^MCA$XW6Qn&SO`R;t_1-6ZNCt9R zaHrdndkJG38MP%ttICtxj6l0R(01hQ1kH5b-mNzHF+nWdM{|-e^*D$PW+dSONE+n# zAk`ozK!$+)24ob-QIJWDyr3lfV-O*_&o7ku5Fai|!fr_tw)-U^gLv}Iu*O9Gn*0%X zO4mRQj8GzEgItuk0l0mUv%o7Cx%>*s&zSryHD!{`tMU&PE`#d;XaH;iYzI^TvH>h$ zHvnct`=Mah0Zs!t04D+MfM&o}z#Krf!*T;3wII-0J)+eHcyv(_`UB)X6iMdEm;#}o zfZ2MYD=G266{sQn@bZ=LUq~ZisDLgrywSyyrDI1}s@bT}-v8+ZxmT1j((19D}cz(mA?9W^J7h~6IqA;m6iC4LQJWXRji z0(l5z5p-ZnsJX831rX>B$crKvlTT5$>&RLNv2jOJgFKGVA>uA<)}cdGAnFV7$&>g= T#_C^_p4DN>5xCZ*bG80|MRB{_ diff --git a/Tools/bootloaders/MttrCubeBlack_bl.elf b/Tools/bootloaders/MttrCubeBlack_bl.elf new file mode 100755 index 0000000000000000000000000000000000000000..a58fc9b8a2f08e5220478bf9700ca4d496c83a2e GIT binary patch literal 486836 zcmeFYdw5huwl-e1_wMxWbUNuIoum^&=%hgd0SqK+5R^_QG$DzAfF1;uP6FB;ZsDTh z%&6g_B06In&_Tc%BcTa;6vK*&8%7rZH17bK#NC zoGe46Gvls9MStlU#`fTXCVt#V8LlukoVg&^^C4{-%2?b*=}n~yYbs@~qev%l!#m2~ zr8B0I*cH9V)?hj%$e%<&A|Mfv2uK7Z0ulj+{~uh_F8!bBk*&QYO#e?@mI+M199Ipl z|4A7a>-_ltB2O&;?RKU=i0jP%(8jN>_&@hAR#xnJ`Plz^8&AU5n4SNZPvry)vG73G z%GW1UG@jNsmf&u|efoF$b-zEwxbF9yV(fRgrhiww!jQC|p7BWg>E(}5%KlR!q->1p z#!_a482j{Z_W0@FO^W7;b2XlJY@}RD=->O*&1dquxpFrD4t5-<3Tr z^CB*5T2|$ds%_qD+OI>Z7gxB8xiY3XFVay$kHJ>ttfSg-?Mq(u_?)mdWaHGcT`V*? zoLrs!cQPe(_nR0S=+A68F2;0RF5>rG0~)gY=+#upTqn>+FTTe7H8f+)H}*}x3MX_N z3_R&;`!D;Zwy#5vF!%b?$s6;1JEt-i4{aIXq4ELtmw~Q^7FV^!%|^HzmWL+C4RbGQ zc&6dYh7l_kt$1d|mn%lByme*s$}d;4knMtNZ<0I4E1`pDHJ=jt?5xRmwAEg2J0C%wDxuc1w!JL$dYFY8F0fGkd6y5i&a%+UVbp&3H(i>qyNl|> znR$=i!a|Ro+u7q%=X&Rs>TTv0QCQKM zSdyvJl^4ma@Lf{NLP-~X+oPM>y!q`{`xf-yckX3Y>KoCyGB7M6dd$*Ih+P)4y z!o{8ZvbVTIOQcjB3|RN_(Deh%ZLdtKn9=)#6+Dyzj@rpq?GB{wbqDxFx4#Zl9jH3L zUNvM*QEOem-Kw})Xx;ho?mEA{jkOoU?(-Vc*NkMY22sX{su9y>hqcT2c-Coed&nE^ z%&T@+>FmqYf zt(nViTrzLrjmzfUI&ay$pf}X0%&VCf%!@v=AYrqzYO)}q=aAsa*KL)FRjK|VfxLh# zcP(o2q;EY&t9>f@d44j}vpr1La792c4xcf40Y!x7HWQO?>Xz z01K6#f4MSsO|!4L^`#1)d(fZUU|?t<_}T^L{$=GeQ3O|jBLrK~zDmcgs)J$H^i1btEmhR} zh8HTi7WBVY`#gUBQzo&DwZ&B6uF76ik7$vjL-QfEqtQY>=8+WJ>dOzsrh5yy5UD4ZhLlwIO zHvPBwM??OTb3^yC(av_vk(Nl`gn>GEGr9MUSJ>#uy{le{m45lT@$lx&vwM12{QgsS zt<4IlCQs=0wJ5l|~z-nzrT=%9plW%Jm;n#72L_nA28|V6J~0o8MvX8jU_* zh${?wHJ)prm+6}k(i4+IJZZ+s>-eztwV|b@YkN!h+FrGEZOFyn>EVgrc6!2YJ1=?_ zXnxiCT37mWTCOKt{W1&PdiD}($gx)BcwXcvw|yxv94k^*?`EN9A@|sh33;B72XcQRAiU}Qh zUgGl%wLd4M_w1&bJ`s6`^hf#*pD(Q7A?LZcuP(-{DNN(|-d>aNqE+OJyd3F!`#j!g zg*?R05rU=to$!VA|LIGUZ^>8e(r>;T;p_gA=FpNbdh>Qx5c%%V%QQlNepcC@J29nT z@^`;}neUnvc899sm>$ISM_gkrx)zz4-fUs|FrDcto|ogQ!$mqjj6P4}c^&jfc4a)% zcizw0n7^K$s_bUNF`90V3-fCoGyW2u+c>4{XJ=XAyzB-28_x2MW^YR8-0*Ow26*1# zuxsZyUxBY_hs3mWoZ|crRAGCEmc$wy$g+UK981jgD8ij7nf7`nz<@# zjk#)eIM3q_{AbWq74Lh=$9*ne;oE+^-(&s|1`RDdboY5nwPm`ifsH5(xYw-r>c@C! z>G`67shk(JoN1g<tDP>)7jJe1zXdYGS`Y4orFRt%tj%828kr`~4FRFxGl z;a$5uYrR)FW-sR<-`jXoO{KhKqol=rt>()QxR6qMKEIWywy#T&d)C_}D2Mdym__u? zJ!jaxrlYVwbLSb|C<}IY)&9A(PO<+WGK^O_$%A(0(oQtAjH=2GynEWJ4o|4t>p7L` z-RvFL;W?Fw=Vf^2;yI>Mb>~(lj4+*3-8Tm|pVeL7Q(WEQ9p3TUnZ^a~j#9zp;;BM9 z3{Nwjdi%J%@|=Wnezn!t?9Dlpc9t)noBjA+)yKko$r-#IKJHT7hq@-`S+D&=S5e;Q zU8Q-ScFoKCqU*-I&$>pB*x()7z>jUsp4Z^XYG`x%&S8bCoybO?IFC6jrE1S$ zH}7+FV0K!NN`5Gty~*SUo=M~fp0-ZStye1D>(!%cP-}M>C4YyKd%ILOdK<0YU{{A- zC0}V*s%G>y&e~QZ@UbhNs4VpNGTyFK&JM2cZJa%uG@)m2VeZXdwc~d;y*q~&o$bQf zgB7-v=Qz&tB&*NAck@{`^FA-{;XJN0s}-E9F{`kRU-h>xHma}F?kj}8;!}NFvr^CU zA#7xSXTwybT=i}CDjjN=59#j$j~Nd32@CAB*BT6&j{KR*(^m4)V=9}}=w z)Gyt<*xd`C>Uiis!?tPpNV)Ms{Zebi=Ec@&Wg=y#cSi50MOMGsK|P6umcLcf=D3o% zMo(h8$D73F;<*FmY!Lm=iqfrOe8gkzZSo~_SgIK2bVpvK?}doTPh-WfQw2M*@j~_} zzY-`5B$si&y4N`s{xhZWaG)%-Up?#xSI#_t$5;FVzlM3RMl0E$XE8SxH>lk=(e{Xg*U<31gwz z{Vd;iT+huP8tHpEGUK~@S55Ssj@tM^T;h?sxP++w$t49#w|SM$f+eirvQDFvBjJU^ z4`U@auEQS0j8f{H>Ncl#I6`_-LOaWC%spYQXfMT^beDK~cpW`^8&`O+UbrLjblj?d z>BwVYza!t53H;moivv&Zd$y~=|4!GXA&+^oW`|#s6C! z9b1?<8c!B2I zA6_`e-g$Y|R$b z)j4_^@1D)~o;!W|`Hi~fZFh&vObwaUvXdTlv%h;|S;(Vq-AM7R(hjel-bSdYJq zg@!2}i+ZM}%)%Sl2m2uN;GLAp&eV9gd$VVMxN)3{{vU2h^Q{ZS1z+%5eQSdy?e_)l z$ZGLwKJy_bz6T?Hofn#e1?9~(wiC(6#`~O*{N}USjT{X>t z`9qrh`MxmbO3L;6h0grpwmrcsU_HqfcZjr_FVw+y9c-t-_A}ja zdZh1(3tnGq=7~V0ZwqXD%WDU1QxBwE8-;CqOME#Sey|2B5WmO2!T&4&+M3cDrADo_ zx9KhGf@Q(YUf#Jbu&#AofRA72pO@{e$!zcj)!;TSKYTDyRzp4Ug#q-|HhTB#m;Z53+`~F@NowVe%#Unta=Q9pUUI*CqEuj&BRA!?$p6o^OILA9e9WR9~R= zI?yaM2f2GX44cn&YfKeiXY|#kcJQWr-*2Y!?GM4m7g@u~$<`-bMx77VB$qRR!a6@k z{i#i<78yQc9x`e|^{5NZ%dV}-X>bQ?fdbW~?)$o6A1HZaxNU-{N#bBl!oX#H&kiDsW$lciJ&TCG z8gvPstx*}#uY#sDiy<3Fv>Mf`Gi2jQ?`F{Sevb6*YP+%}sY=DXT;^ZzKj`P^BkJlj zA8WGuF#oS)JvVW(^7;VVQXnMSnT!=0X81_o*oeBPux%s8EbW76qGv_=p1+{D-K&k3 zrgwEo%fX=Lv-yU!V#SY9wK+1K&BLC_uHEyJ-k2xP(= zlaF_BS4kU(PyL-Kcir?LcQtu5Pj9CQHRPdj7ZiMjeA96xyk!n*xhg*pyo-f?bk^l7 zY4a?O^c{<~1HHHJZArPf9Y!dZBvqMKV_&WbdjUNgl#xF6IN2cIK0R;2x3{vzkZ5Pz zD+yD=;JFLho`$wPXp=9~nQp^n4Y=~wq4&q%rFO4VnrbTVvWzba=dn$9rR;@7-CCo# z)z$mMTO3B4kuN1J>b;sTb#GI6PT`BKuAzK{k{jt8AE9;|ap&?7=PdNV`3>PYGpSVK zjrGahSTSQHdp*MvPTXq;GnA zQ@FfP4f$19L1t%Dc#11`RD4I?D9kTvVux!~Qm0^@k>-0DKw zFI-=Dunv2Xpg7iWXshBYTa2Eg`La5xoiZ-!JIS4_r`nY7f++zu>P*LwO?+airw4teTshfg8CTLWGo0)BQ?v|tGdwjg zi&{_pB(Obrb70C|E!Xdi^wkd-BZ-I1*olqw?ThX=mb6hDve0kZxm#_Zk$tdceXUx1 zu(qsLty9;Qtu@+Mi_W2JM5+Hhzo}+Q&3!dkD@8DV8)%+~offLK$u~22+@I)k_?&y~ zc?`8((7!Vnqi^h|y0v}X;6Z!7f%WHuN{B1UTCaF|*RnjN##^(lhKK(4M(8!z)22T7 zMSzcZI{0JH)n!xGx-s|c^4Ix8Z}X6)6>bY1v(Q;6bWDGzvmQDPEedwIF;g|{3|G%= z3{S^3W2R~Cl(n&XG=__3QeEl-Ljvx-w0iPF0egN_tuth`OLJCKQ66vOL$75DRi%C z%1L#E=af?Pq?d&f*UmqxjA5ZaHBLUt@O+?=XCkof?Pr z6v}K9Z{YmjV|TmCwIy6xSawozf3|qDx1{~^x-DnR3%^{<3TA{{YU8O3jb!`38ZCLq z>7sWw%l&-uuEo?NZo~*ANkd!9nYH(_(B8(DGoE{=b>KVt-nZbhuaFn~d*^H6>Oyx& zQJ=>1*}AXlE?Ic6%X5m?J?YIk+Hz+9@`;C9&g@*?488KgS3xC;oEyT^3u!G|CooRk z%Z2|c`VMn9*L_~+UbwTX<&1s#_zur^O4*a%Styk)Z|u~1W~j||+&%mRW&u!&`}4XH z3paHc-rU>U@Cx};27g|MY?`Ykuq9kkcrETz?Sz8M2Tj*=Q)ypm-YaE+<~lX-dEL`p z?loG0z0(+%RQI7wt-@QaP;Pr4GmoHF!(tvx28P6yg8Qt}Cky zpP2helwV;_4mBoGdnNJ24i?%O;rVeL3U-#VUl|L{6Lq(BjluKFI_#*1)V+R5$n_fM4>Wp$O?ee9q2IfXN zk-lNVw|LQy@zpDyh6ZzI`7(w7=c4=iC2i^wbuX1fwzUD6R25-<8&;dWUwV_BN&^b#7NOj#$MQ{d;eYUNB~|gP1wz2MSta<{84VM|r^1A9!q_-cEHI~ZR{=WB<Q(g`GYD0oemtgq-qm<(2bz0+q?CmdMk~Rx@TAdR+)GBAE6c*!qYnhi z!uHWho*LFiGu+Lin|qwBVQQ{wtUC$cNZ+3$46BYv-`41iM{9Lzzahc7HAyafqZIur9)0mT|28kyS^QVnyV@LB8?csd_T!Ycs$pt; zptgp&ws~j!f8$p>NybCBw{8w>45-l2D_!-o>Qk~dd%KQ3k;O-DZQq>jEH|_QqP?kH zT9*x=uM=JdqG+R$aUCiyJ~FPtiGI{D)l|_iRUNghU8`W-2gG;EYuGOf;L@?CYiQZF zhrb->(=iu1@cwxW{d}M=abW+xvh4Zn{;!?P-JrVb@D@^vGkwSRHF>ojMdL@aur5A% zlNMG+Yhj+vi+bS4;CRK(&tLnQ(HpQQLwjp>%rvHv>6jO>noCpD(}xd-1as@%M95~{k>fVM>|Wa`oHP=0&}j8dXRk@ci1DEhI8p2ozZuZ zspq$f)?;UuX_3B%Bc?OIU8$j`$4xWF+`NCq^g61D&H|e-Y9^de~IXOl`Fp6myeyy zNZ(O#c5roLZAbqSez*}=lN%=yO*?Vz8N0^UdPxJFfg3BT@C+W>{?>@GqdU!crC0?H z^o_qTxAl`SD|Gum!8w1Oe>=`5-7C$PTZ&I~>3P$Hj_bnC)}*Rk*{NYZ%wm~6<%64* zu#%m*hTgGCkD?H-W`Eo1EY>f7uj`TqemO7xRoBPS`hJCH6874M;QAA2ivFNI&QH|y zAJdp(lN68MV!@98s@6zfD1y_6ARE=*9#=Wfuk>sjKhKYuskgB<%dfXxbq(fp=)3uC zQ}h-q@@z()KSZ!kMW^9joQ4Omk2NdH$RnQM|1NJvenU&@QER2OI(1E5t93d?Pfa;a z_HGEfXYwLv!N~HyPVP=^m=ks}v;nn4`wo;l30D~YbL{*gWh&85^!|)|>UsPadLU-% zjz}ERhZj1_4`f+eIb0cG~@+AN?(o;NElY z^eOdR3OmfpPVUD!Cw8Y-(aOqNV-1$|HWpbiKP|v_SEO$T^4=r9!0et#UmM0D=1+ko z`b=3$h^uM7vQDLZUyrhU@}bdq1ExZDRYyT}q^}}!+Wk37yefiKH zLU9-6*=!%R6rzTbPVDRLnwif$_Nu~`?B&BX^T*lC%X``C?Aye%Jo`2)-hn`PmD{hB zTL!HZ3M;7Hg0iq{CRvI4)xbPt&)mZE`15qqxj(|U8u2ma7Ug-Khf-}Me;<1;m{rd) zrlJkDGcV3ncpjZxtj3<{lkgj7P;?s8PIO%5>;R!Q+yCup%lbgkdPG?nvs}Z}!f)9L z+P9(ir@d-^Ahnm(IXim(X1@x$8)k$WSCxmWCt0gL36zKRNl*6#RLYI-^z%-@qB)-CdcD$8WtsMnS37LM?)PS|>2Sl;S-`Liu~nzL za39j!^)X_hno5}~cCBAp*uwIj43sZT#z}glQ0w-l^6`&(5&w~SFl@)ATR;y1jZ3%w z?a+)6PklF>T~gTgAg6Ny>=g#L$DRK;1^eKyz2mAcmllI%yf1cv#Z?$InahP7AT53`+!(mAG0?(51fx0Y|gI_(hlBFF-3-zoZ( zshUPxQFumZXIb4MrK))mjWbI7(bYIFUc(C-TJXKyIjX9B=~nNM&XHB~7GuX;nO8S& zsdz4$xAY%lcM@~UT=RnieJjuBRDJHx!N~$EVQ$>7+3$Aymo1&qI}=}IML||@{y29R z)g%CuQ3FN6Ps|2B!$DITyX0Bya?`%;;=sFMd*Bn?9k{XsRju(=&9rtYs>6;ooeVVl z8`|QksQ;4hG`2hr=24kTVUr5?>$t)#7a-{q0#mohinDCH5@D=xttc`NMZ z8*N*b!i#?4JrHI=T#FB&ZE;yo9kK@Mmv%3ztF^mRYtn=1A$#1pPHNBJVTXp5xO)fc zsHV-B$vp0|kX>!Av7pxW5_nw_U)7D(_Wm;P6LmslBB&sq6S|kGJ$40SGxg-6=Gt)E zT;T3$WOnb;rtow-`h>7tc9N&Uo05j9w9B8kk9FU#+tBg}_N0Irr@>0W%nlXT)sC43)>D+N;OQ-Sqb1|oQv<}>dIoi2P!P||oivLX-c8B3ngwpZFcy9-KgrmJI)QGb!HhVufq@yTK~0!8S}5T zA{XttDY5}`F|`}Djdp7BgYJ`xx_Iq}*ul#6DHTY;IVh!zF$Y{4fJ@oZCBaJqU->Kf z4R2+YW6$1oAZ)jc3Me5};iKYFZ}_dN-ClE|;t6RU z)Z20xvmUiIPSnc|hKrpIZNPjiFn789uE5w$8!{;;pOjVp+PUv~JtyDwyx&Dj%^AjeWLTSlh$;|K*FJF6-SnyW2m`tR1PtOljSFN5$5u zr<8dgzp5l0`8YfWE9c)l#V*C1XK7x#J#cp4L*7R00QSXY9;sOxUw`0qe1;NAQkC9N z%Dyv=m$A@Ojr-1cE{pG^vB=LfUiV4BSx-AAzwmmHuTVV_c2=Yw`BYVo&^ln>z%Ec6 z)XM{PpeQ!%xq(YTsi2w%ZdW%PIbk+*3nNc~BHe;WEhy5xB;q#TduG)ur0t3<>oPoc zUgYtD{s+#@pYpTAdUqAg9V3-qPab)ihyKJyvQat5>FEtM(TpP#X zPheL!OJsR=-_N`PT@8D;!EHF%-R7Sc$S7anpV^gy_%*#<4?I3)WBbEle3SNYWkWlQ zPw3$Zv}Z=+t!$~-{S}@KQwL=eqOu7W$tGg<{3pGr40?qv>JGkAE7H!X zBM#PR+toUjYZ51&zw&!)6zs)owcgsbwZEz@tE0Jy<(1Z#*6^AG{&lqnYU#{npzl5G zW2iX4M0`x=fk6CT`g(Q_#n*E%(|-Wp2?zWKf~n=}f@%$&?v~Z7H7s|a@8|8bi)QnE z9+F*=_PY;d5O|vjH3Ng74#S{+_pRN^I$zCUy>YMO=I7oS04=!jC*v|9Sm$ z-6re&tnG*>-R^s<$CEVVSdowScod4?r#0rI-m{&}^`0Wn70tDt%Xc9MVogNpk4HAa z(v&Gj4^e3!bQSvM`7ZSR`a*O4{PJ7Mn`>__$F3y9cYtUo^_-S_P}KHdt%}ytL|eTp z+G?$6tFk(*<(N``!0)Z67G!zfw^ZnzvY>)<=8M|NH#4kFw2F6}z_#dLV2jrJHQuM+ zx0gGZHFQ_)XJ~_eY_DdVre54$(LQk1zvu%OwHW)mxPbfWFK&EDo(?eM2Tmrt8O-=&Dg0BRHqK<#GpJ&ITWoJi;!A!V1m>icE=44nN_EAK>` z5yFL{&34vz)j!`Ir%ulL1y<9;e4fjO95eNJ)a%1qfd|)<(e^@XU17A=_oY4-p|+ns z<=7!A<)f~VzN^q;e>>k?Ke7C3wAeM}h-^i41mS!zFobqNu(y1!YkfT{2zO``w`ZN{ zNcA5?{QW`y!C+ST`k+!nu>xXb02S{361(`ttt$3?=hkJ_D0#=JecEa7ibEziLC>v= z$>|%%-jY#`cg6XEzW9O0ytHXFejd5N-Q{6tg1S1TDy8yRAh-8KjYYF0#FyEp9ryn> zfYtoU-})1$#e?EXyx*R8{7zTi`fwh0ndzIV_H`X^eA+L4xa~alRX1XtO5a#a?Kg$! zX=f*zAS3*TRsSX2*t95!^I0?2*7`B*7+g~SLg42^9`_DCj8=(%A>gh*5>D8YTJEkb z2)yN8;D5GTiL0x5FPzZG@jnku5kfRScyua_iABK|@y-3kq2pb(!8g4L9ghawwLcm1 zxc|9;l0UlL>D-!ayitGHPNUG+$0Ur@sv86I0<*H3yyuPzeBfhMpv?bJV7>ptz(GHD z9crqAYVAY8vRW(l&Y^=nxV);oimagLR3tgRO#J^rZ)9a2Fd;f?F=TaFOL1R>|IESn zAnngME0msWj`*EO2B;EHzl)@SngilJ(x7(JsBduiNb#~#PUx=K`cGjux!b&LO{t`@V4_^g@1nBAOzsjJ8A zLbqd3SO1r~_L$vz*sYJ*J@rn^-;64I%S|}Vad@=eH7n=UG{(pFu36+S0-P-}~Gn012Qkl90X-l?FZ3btm+zhS*oH4VtzXN=uxMW>a&X2tF zYHFdMUYWWSxtDI8>IR2W!F7N;p=n2wDpQvsZQ0hTPk}?J;5xw7g3~Kgmm_UC@_|FC z;5xt=rEVCkTU@T*qT>y66e2>Sm5=a zMf@@K1J#!t<^_mAE?}cbmSRsyO-W{K_MB^r#``8uo{X&ARfLyIDd+ZiT(#fG&GvB| zVn%V=l%A?FHV0=4L}!A&B}(Ul4n%1>YoM4)!)|fmnrI2d;|HnYE9TB+>~XUE&%beL zOdpEtMqE>HU5D#xTqAL%;aY@?as?4Tpk<`y@d0Pw{gYNR6~W8W*T|z;D3j7636V&+MIKRRV-R_+02#8Zw;1BFJoo5 z*Dmrdsi|8$#*0X!*;8gsE3F>E*nN5MBNuz_C@%=Q40al@hi*~In8Mlq@fHAw;1$kH z!x4XK8qOKlhAWC`cpT$q(>fIgH5QFCB_0{gCa!qsv6dbz1=riKmBQ`thIw|6;dU5R zR5+@s7Hx!gM(M2b5#PJU3dfBvD!%-RD@!JnddteE_+WqxU3`gJ5*q)_b+Ind|6lsh zcrXifABwia*{_ERo6KBv!A)kzvk^}Z7{Y#OO>h|=>^Zy-ok*j8OL{LCN85bil0}rx z*xFI#;tTi@7m3gvznuh>@%yK=SOT8^Dy?zkCMrs#dD5ofH4CPp!F*=}{A)xLMbpUH zKBK%w(ZMJIzkg-ZNcrEV#XOGny;vUkln6)!BmxoviGV~vA|Mfv2uK7Z0uljKbkxlbHVBc|EnP z>?&9O)alo|<}6>nWR>gII#S*&vyd z2>RNekVG@hhbeUw*_*LbNX*+%hWgVuNP_!FqMIKh$pjP-=bQ^kTq|yB3+%=XUqR#z zFc>#_JxJ|i;zz?=T;XHHe?j~f7>k?qOCq0`$e4MQFz_)9nhOL;-kHY=-4>K(zD$_; zoXGJc)e4}izK81S#Xib*2o{}|pKJrI7oxJ3M_vTU^!YHu-Qnz{yvpo7ZG!yjU zaMtpCJmhx$%M{QrN1&b@e>=0Nocfr9ssBahCp-fkt2PmLwTH}1c^!B2ez>Ar)_+2h zolv)IAU&o(hMHUMBU)qX^=3$_zXFqxjZz(!TX;Tvvk3J5ygH^Vbz2zg3%ndty0mNpxd&O`SqT-EbYagavTTVVS^pg0TtTuHqBn zBC`qSCJIKgnO(3xi7y5ay6wSaFjouj65<WeK;k6P}BuH^>qM==TLS5%rmOvZMjFKU(so(hpo#m%yYPbD{*nhg;3MLCpZ z0s5!M(j@ZRO7oz#g%jw^7KaqeR#8hw{KDGXm}Q4>Y`87KijE*RZ* zDRSEG5KIDU3Fc10*yDXpvVC=RWD*Q>oIBaiI2|pK%)AlAc`!5tiB-?g1YH!;q zQe3td0GsV8!3?*(OKQ86yJ0ln_E)rpty!cL+TNjZo)%28EuG4FMldC|I!bv~n4V;7 zAk)7TDIVJhvi6){%58rl=6PYd!bbhm_JT;6X`7D5w!J8rIW`v+`jTMg+P)&Smxbw@ zY)h#=yG4rMrV{gtU>4d!q_#(x4%nUqkhZ-dr6Im-HlW%knANts$kA7Y+8W!>sM@cI zltxZJVwxKsSr0B4(SYNp*s8fw`O|EfmafFz{fJVDiDhgIfhN8Vo$RO)!OE;6Xqz z#qq0(;6YF@C1Bt|y@J|kUZr5Bx5^Fd_QW<#Wv;)WOfA0dgW2Ax?KV3uEt*){ng zl(P)7ES9RF-Rv2>4xIWbZv5^0a5vYZQzr0_T0o1}A^-gqD1ce&Y8n3zl4|BckjfA4M}k#*ANRyg+>+=9!4L3AOGw_uFQWlA6{^Y2g2r@*IWPHXemN2}+c6B& zFCoec{l$f%8Q#wS*GH4 z6E4xgF;7>6P92UaCpRf1A2J#_?gt^>n@NHq5e&X7?leCLr56X41Qk^xSFPGlNr_tL z!$BoVK+3U0(#FDbuOI1ih5#8ARLlT0ow19nlW`Et1b7+NnQ5^lUPjtuKWAlsVL& zTuiOc08?s5f>le$Juw%zB)UQHW4NO}jp30}Bgm`JiBgsdas!-6-9n3^Y&~^b0Q%Hr zQ=hq-a$0Iu-o{d&ry{Tz`v~<*eX#-w$)vX)SG1d??jc9J`6`Hp@;c;9o4Xry&ID?q zoLf*F&#?g+g{gmmJng1Oa91BCvgTdfhY=aj(tcPCCCeR4SF^Ocm&0GCf9QtJJv1OR zvE)p4(u7GgSU_q$d#VcRtOVX|YBh4bJEIr=YRI83X1eej^k#TP@nexhD$V z^Q88gVB+H!HPkWZ8+-xO5^SF!qqCjg4kp_+4Q8D03nt%|OL>0FM!;#fM3){Ig7o9}I0#)AMM=T0;j%ee=Zc+StE zq~!Q%trkxqny)g0fXr? zxREi1-ww4n(oGMctc+{<>!8t7a8LX-Zb@{5;HU66{X-O(aRWalRQ^IL-^Nsus0*=l z4_RHn&j}4~hek4P!blR;h@~H;VixnE5L-1j?nCZJ(~OU4vGjfdqk&%|6v|1V7B{*K zGt{|_SIh^XVB{It&30vu?1YNG68$N2)VGwPzl>YvXreX!64W|#4AHtCLV=lMiB8b} zMmmK=+w}+FTIP779r~jrFCyBhzeDn3qO+NLEozu~c>rah%&Vs0%ToWE(kD_n)1SpH z^J=0s-3H7uuOV93+eq#qIzcZZA4`djmRUx$Lw}s?loRdLe@?WIXp~t5NHVAX$tbhB zmCBrsR?oba(xYY0AX?M!CizUFqh-z_IzhKl{bv&$E%SP!qxHOj=xCY$Ml{M?PfpIA ziL!<>J7<|UKjnbUljyLSw~z|cuR(9fTtKv@{|Ox}(@(UnZ$nSWtRXrrEH}ne{~H>uCh*5~4@z|3>sO zq6_sP(aVW0)`yVy4Mdk%%BGdG%oRjW((fYQR_;YrJh?AXH&{h-#&e&f!fvO}2aV_M zBCR{$CoP`4luWG=YFh4EO1X;|P0PKCy21~L(Y4$ogv^hKNzihiA!~ONW7l$BRM&fn zacH@B60?>Vr?I zQ>f?uky3ULQ>^D6pf>(FF(rC#KQX@`W|E#u@MrEEh01yK+%G8QDPkJ++!U(mE@JlU zuHYh;*?bv6U~w%6{q$s_t+@|Vk`pP7s6MV_IgZ6Z6$;{(>{y|shNauEYnVqkY*wi>@gpjA?df0=K5a z!hX`TN8c;-o$Yi8MziVYL{6u8$>_HEl;RdC2`qg%nH$bOGAxbc*OR4fq(3HV>6c`7 zT+|YMgF7!5%Y>*UPt4L9G_8@{QW z^97^ZZUrDtzhDwgPC}wyFex^C1~O-Zu;q>Zcws;Iw=VngtKh0K+ zUhaH?(<@WAO+}w|J}DMM0Ph#b>HGzc$0LrcShYF0Cojj1F46QVq$ZNmHvz4igj6xs zgR~41yct@JXalSE8{AXJP%#q}dcTkO73KzIv`O7DlDS5FM9esos*MG6jF>4Vb;)?< zx@6u2FtcbeX;N2DWcsCNky)WP62>YnzM}}+kNK+>HjtEP`im5=!zJ2rH| z^Bv=`0v-1b*mk6cV0S#9sjSBRI$k)Q&oZf3C!x=b>xgQkK>Z&zt|g74&!QUtn0hm% zvP-uSmb>{5XkjWr!2v4xX|NtFh;K2>8V$h;UV`{T;qN}mR?9aIX8Q$YYl>!jES8NL zlND?o%(fWaPnp424`%xVW&2Sy+wWr8s6()V4Y6#+_fs|(zX>j*ufoZGXkNYo?d{_9 zS<7d#;%lhOFkU^VlLP;S4vXnraRupwCk?7l6|W>S;i#38yQzWSSON_lO~iLBMq^D7 zJ?jnXST{p>)$L4arO%x$#Ly?8^5zHdY9FzyRx;%+;yS?LFov;HC}UDBQ$A<~b2Zu9 z1?#ZIl#f0|+NgC9orU%_cY+v8370(#Dgphw$O8zz1VfFt1}Us)79@W}6OiO~2qqTd z){8Hct5C)tU9eMtjFV?VeU!<70Il2n~i1D!+#Q0bZ2Ki_W_6!z4HTXJKgD;Q8 zY7i5}Y7paNHHh)C8VvH$8oWDL0M+1ptbmhOVN8e`#6+Mm;u)GDyfgzmLo>jnRjXGq zv4)A;$V8cV%iKmUnMt?SEoMsK3o?gn zL6NQaEu`>u>S%b3i4n8Zcz~0?XjKDAY1^2N6i3rREMKou`I&gpmwyRWFBGSgARk7Q zdK%LvOQ!v95{s9$lf{uO-+eH^a}?E=jNCjG#4jPSKgm_!K}hTmf}qXPq=%8T0TzmJglx@25iW`y(d6i_iO& z|AX^>^}jpsSO4j}U;U@^es#u96pxe9!SjCgpU(R=ao(@di{bl2f9?B2f6X}bKZbO1 z=&u=v{(mL?UJ}yDzxMsfzv=svf7ACT|E95&L8X&_(`CXIo&1}|lT^DLV2hLgxZ;^0 zjgx=#Po4%XPX5i0w16~D{>@FpNGwkN&5v$HYZ@p2=I0%d8z=wfmo1>_JS*?T1X~|)nxSKKkkP4 z5E&=`<_Y`-FyiFjd=;-=O8ni!E1QYry;k9CW6eAB21l6FKINY{8!RLZ;*_KesHj&b3dl561WxGh(nGz;uhmnV; z(6P1UNh1?aX{EHE8@YH2omE?YVPxYe|3PUxjeJT9ok?4s;sGj5Nu4&6S$6S_`F>QiLh@Xu}1n3uaRMOdksU4gVJ9c;d^6`9M^m zBEA$y?3UjOrrP#H%JU(oeYlyn`-%A-cZ2a8UE(924`#LPAxinZFulny<-5f9ecf-xct#tUPL@3{oaED#PM;`e~{FOcu49XPofbINe2%g0oy{jCmzNviEa@52oGn1 zeHR~x!6qUe?9GBUA|C8d^DB{HL_F9pj(D(N9PwbkIO4(neZ&I|NvlRfB?I#Yv+w4| zP+lCJb~>ivb_=f9ke?1ZlOi7MO$y0}jYf`*AjEnhNl+w$!4JfJc}(f$K_x*&m0E?; z7E+?t`Djpy5@4h?mhxFF1;WEIA;)6cD45ifXvKl#uVcwW29u*HW(b7GlLu1fk{a7>35@xtGAgE}JOf!Y!d1R=dR;vxB}ZIBod56M+#Oo$@lA-URENm9f^ z@2GK^uL-KV*8xar5vxqh#9+GF1Nh9JRc@FvDVj|)pxikd{R?Uff zq8qm)x zj);dSsf?gq6~{drNv@5chzCbB;$Z}RYC7(r18PJ(WKhIIn!*VWrz6eIX_rq#Jfu1J zU*V4t@sO6ue-GM-ct{&67$f2#Emtr`!~?$Js6Ix-L)ysbIymDAWKA2z=OHPM><^`g zhqN2`Tc`l&B9?YzjJ}ekEfTa5@!)7!0zXB>gX5xz2giz^pmP`z4~`YDf;J)^94kHo zZA3gcR?vttA|4zoXdoF84~`WyYK({n#|j!JM#O_-1&s$I;=!?k`aL2Zy5Oxx zxH#e=;}0DBxY3A*jN|+PSTiCXGX5+IH6k7|E{=G}xH#e=ZpiI&_v^!s4>Q<(P-RW^qD;O81=;^#x2npqu>93>eii$ z!Kiuf<@{mr`CJI3LZW zf*ud>{&`kZenXXajY=t-5WFjBb-wzmXhg8imMFtTjFhrORs}sC%8yc=AdWfJxOUo( z(l;0_tAZX6<0NUJM79x{ht ziS;q@c*xA7iuQQO%qOiq9x@9^YmbM_LekpfA+w0I_ISuFCapalGD}EnkB7`s(%R!8 zb0lf)@sL?gT6;WXR*=>n51EyuwZ}tdHEHefkU5&P_ISvwA+0?gGHXd|kB7{ z;~{fAnYdF;kB7_&WRgxbJsvVAl1V$&o5-9*CgW7o;~}%{d8Ctfs_F5NIfWt3PBkaJ znbY1w$S9`^JRUNqe+b$tsQx2kZs%IBRai}rhs+s_V!74yc*vYd#&N6Z@sK%-jO$j@ z;~{f4nYdd`kB7`R$t2xsdOT##A(M8i>G6=+NhSk^Sv!wR-mRv`LuMD5O1GLG519+d zbaAWc@sPQYOgFch9uJv|$ke*k^mxczLZ;5GrpH63jZA}EO^=7nWn>1r)%1ACTu!FR zt>!ywW_K+L*X&l);~{eenQyq&^mxeZA#;!01s)HXEBmqvin_q#A#>FT(y?lKJY=qx zx+$rq$3x~C8nzPE9O*NAx%%uRs_F5Nx%LFcN$R&owg;Il!Q+9=TwW!4`$Y(khue*i z_ezBDc;M2#X!16R5FQUNQ^+S#A?%B=R4d8yJpXxt#{%Ie7~CJYi`}O!oEG z5YO_k7!nST2Zo6y7Dq?YgFZYSj(|u!9x~TG05h35{2cFwOgtVc96ed?*h+7r(c&HemJQ&DysW?RaftL7UUopWi z6+Ir{oA)?|2JP`sF-I8f@ldfq813;;u~eoN+T)>Og)k}cc!1v>Eo+a5ijC@zOiw%> zDozkJ?eS2tO)^=Dp@@|eb6BtndOTE|q85XW{)G{f6=$gNn0|=IL&Xlop;LQ2RGgMR9vp&Fc77cm@^aC^jci_m0M4b2X1vrb8z6iNu;)( z4{{nLJUt#x#yyBR598|5czzuH7K95TsAS)#vBb|;7vhd!hXOET8H&UO}m*^L*xkUeF%_aIbYcA2ryODf&%_X|en#*BnJT*Gs51pvl*kOfN>Uv%-`;58Vatz!5oSngidcJU-?UQ4MJTZ~I3 zs5mbX^A~c7>s~n)fzEj>|!f)@?aMW9Ps(O{j@X{3jc zb`w`Kr6$sGnb#H#C7n$4rp_?Z=|m?KvuHT!OrksKX43h@6Vw?&y3#6xPl@HKqVbnA z<)1TT0!b^em@!&Nelmg~bqcxEcv8E4pny#;4T$HCE9NL^CyiomKQhQB2L>WEI^`(oMX= zy1Zir=y>8}=H^b)iPZc>M_{#}7-=LE1DX4~sGmt3#@ye>g69(*n2(>`S%A7s999GR z!Ph}|Ni}GFS>%RP0io12!F-XW*unc>~ZF7AZTRm3EFQ;+{*ks*$ev3 zi9+V*siB}prsl6i++Q*7sKoXv$e*EpOX6F2pcFm(IOr*fpB@DIg%eQj>4~jO_vLBG z=d8pNwD}5q$lS#3l)uWjOR!M_KUA-f3k!wO1Q*Itn_P8CGAQ#Aa?;Hy8f3Gu-Z`{4 z#1<{@AR278Wqs7!#FA^q_3osaX5!um*5SbtC+QV1WTef-t+e+dOF2eD>b&JtJH$Q< zAr0R3G(Ap2270fPnP9geq{%y$YLjgC$7T;6R94YsQ5)r5K(#3nGS-{GbXx5_h|}Wz z2ED9kx~NU@c2I4G&C*WyzE8Ey_H?Mt%CZd?9dEPUj#b(Bsds|Smf51Rr;t0z=Kizi z>}(fmo@UR+{dvjG-c9qT+do0rTQ(|>%}*-$1yot6f`#=fcomX&D2O`u;9C9+s-4Xy zq)w5!A6yXnXZaA*F`ccYSf|4+|e+Wz-H^mX`o(iyU>=mjJIQiFj4O$x$WwB zSc_XR{=A3?eh%|b6wS6@!n=m|OU9XFa|p1!Q)z9k+#APxiq(3!Xt~}ERGVk>+1bTw zV&3M<{T%E42bl%-&4@q6dzc0m+7~0GSzd-YSY)&HFY{(FWU(-7yn7jEi7=bJa++Rh zzk}R-!@Gy~`3M_jwzhk((7=(B&Tj7lsx6Z^S9!Z>ZMiVt^Dd>@3Sn;bE}-e7gt^Q6 z6N|7?nESnNGGvuld&G)y$YGLFA)e-$s_>ZHFg$7a3M>Ck(K@>Uytjy{Z4esOPn#R< zQ3%*<#rRAiDK-wUVysj)ZJ$5jouWgf=N-sSU9{Tf4LR_2=5dqFv~;ScnHU+X5Z+X{ z?UZz4_mh?f!A{UohkdXUdxUAFcZhf|t}(Wh$3aNawpAHry?$!*ky7~?Q~%7~23k&J zC>9TmNPF+;zMSU*ag*)+ow8R8A=aqS={GT1w0t)ve9-adz`7FL2YLHk@T-nc0qcVO@Q z6J9^#32v^kucfp)iU@o&j_4Dp#KFd;dQ!5*X@VM3C#!RiuZ3L6HP zwIRYdUSTDeCUqgEqOQmD80?{vw|EuLW3Y!S8uq<1;&XmQ%lE@b(jKQg#LiRe;$Zq&$?3u*!PHyH z8N#GJ?%_|)6eeT2T+vP*8kvh!VzmD(2q`gEw0{9wR!K@hPg)(Bfs5{h)Nc*qgW$KZHUT ztCCCCWfkgs;AH7Ka@S)ZJIH4J$fKWvmM3N8u_dsC+FfKt9;ehvT#qgkd4fs$OV^S6 zie&UD#kErwmkM5x{C&{R$J2Y%X7C<2>!+_2+Va*TD1DXMiU7xB&r0uA91C3UKA2Bm zCrpvY&HCx@2~+HGZ+H57VPde(z87`aW?eo?(l@9|SWBLQOAPL-7FP&N-`)kfl1ta= zb8X7YYZ2pd5b{W^5Q-ugx^$c{3ByK$oAo=k=)smt*B$lJbz&**ZO2JWFrMIM z{f?7KCliZMU$e>xwtkT@Y2v(p+ZNhoEa@>AFUiu4_U|*O|G$MyM=ZXBL)VUQwo( zt~1B&0+Zrq{mcoR(p!mN9E4(TWruKNHj>#&!^s3U>u0vE0i8~8vwmjlai9mLuvtH| z^=?F++Z9XKK53`9be-AyIOR^7OV^pLY(fj1v}_sQ`tJzA(zVN_YtL4!k9^uosy`z? zUWCH5;^1dhai@mosSgp`0n-m}6~aWp)LUMaFs{eV`d+nSdEzo(@w)qy1@|JD@p`B$ z5R|0-gSd3<%~ZCgVPv+U2Vje-&>c=fgXor7a|`mB;AZ`dUb;?jvwmjnzoT(D32xTU zto<0Yo8o5u%v$!Zc#50#Gi%wSk_m3s&#YxfN+-BkKeLv-CX?W1{mfeSlYD}k^)qYP zA1W~$TnU=(9vfncJ(lfe;%bdx80$+Jm{L<1NBH$=&Ez9+$3jw+d5S#m)M;+tpsE#l2?{G4~U7 zH<-M~&HA|qgz4sSvwrSjwHl@yJZ{#{!7&h3G0@{?{hYsa?Qyey?rHTt)S5kR*3Uho z9)q<}9yjafUXVmvJZ{#{y)2K+NuInEz9!6MkDK*#Z%7fQRB^L@?mhJa3{3a9SwHtD z^$M6-9(^HlA4{8=Yq?yy&bnfuyY!E2iCCzSrRy45x~^G*OxrcGbX^l=m#fiB*DjZ? zvuX7aYS53}S;|=>OV>5BbX_A$*EOHUE|;#eYt-qYz-5#2 z@8ZI*3D)p!uds{lZj7Rq{XDu z32xTUFCm>taI=1XDd~KIoAvWYlCDfFX58hZyClv<7s#(5-7Ue*`uUZlYZKh8pI=S7 zF2T+E`J+iUB)C~WzlQX{6gTVV*OG2ZaI=1X-Nz_ObDB%n`C}-@|I1vu&Trs*f}_%0 zy3TJZ<%Tzv=F)Y3v#2>~E?wu3CF3}0E?wuhka3+fm#*{2lZiWNE?wtOAd_^`T)NJm zNG9#1xpbXBiA=^xbLl$2tqao0J83Rm=TBisvm=W<`O^j=WR%ktOV|0+hk>>V(tpG? zzkME=!Zeqz^Jg#$c6M^~X)ayocaf=d(_FgFUqGgdo95DW{z5X{+%%W2^B0k+b<H0GxFhmafyFMU%Hlgjl-nP9dK}lZ>!b zD=}N5gr#eSNlX?DuFF{ai){8P}V`5VLgca_KtPMU`ty-PL8Z#HH(;zjWMYJv(); zB9*PM+jkjqeJ3^%_Is1@+eG8L(5Qa|dBIc5dI@_d8&(~2q=hp~`NG#Ysu$jL5QySY z)_)=RHxZ-%3=p4!81NKA>wDu#BU`Bls#bdobge<#p@0)O-0hrNecx_EvV(68$s)z} z5Qa7V6vDxUuwb;ywy42gh)->>``3W)fYvRap*xv4Y@_j8>Q?)ku-*7dNEZ1_H6{_m z=#(v1jkIX^)FN%M+P63i3#9I_o|bhzEVUP86X>b-dicV8fN(8G$(Z_$5KLjoF0x~l z$UjpzGNeA3sT&@tOL+`$Qs>~tPa~`9*QPkP+l{Oy!=sv-4J}pG$f`0DRFxFW@TRIJ zo2o(^<6@YS#<<*OV?2p0 z8l#TJ@klqm6}s`w=(A~^rH&Gt_aSf?4YOv8V3sww5!Y61nr%hZ;%BNgf*RO_uLF^* z<`QIMv^2k!sFVf-tF~Q1u0~6)egoUhTM%4{;695iHNj>V%%Mdz9*F8Y*Hq^;yZ-?2 zy%EsACy0YV47dQH!%&S#llym(BUJ}GR?p|yf%1}e9y*gCQ*DzDGBuLdH3Ad0NHQ-; zo&-+!$Gr5%J>ctSAu_s{b#7XG&u1C1^se2Gh`qYyk1}uPv=~L@j zVfH2%lXkKMLFjgt>Z03;;n_|M-QG@&#IzH`n|AUVQqv#lQ(a)35^P%j4RR)Z%E(Ng zGQ8~_W z_wN?#YKn9;>`+8U`vq)`8G_106eg&q_DV5(KT&+j^DSWvmNCh5EV6f6jjNH5B#cY* z_^IlD9C*(B8!rw8L^?lhAN*otu*7eLrV`;2$gR29W@X|(nFOmGu`S_pEupg z@TObwNGN`W{TzxN(I95Q5}Us+NNA`+xR#rt3IdBIJ6rt#ar98-%aFPrs(d~es(jw0 zKEh934^;@1;(S->p~~lFsPgId4h4BdXOjKth4!<&0`I8xIenFP&*@!x@0^(u)%OUp7c)3OY2T9)BW%UbK3l;PqO z7?hSZUaf&aXel$3|juYO}Oj8zu7%&!r``8pqwJ1w9Mn3&942JmZJ_QbMNUSz!%>zoBUVL2DOmvNl?s8DTT-)T>MW0dQvHi)db2K3w>Rz=fUcB)WloBKhUIDO}q)!CAwG==Q1!-tf92v z7fa~75F*9;Jwk@9@bhv37<37LHZJ8l-VfqU4F$1y+x?)QNzhbINeArqWg%76jxHRN z@?VFOEJN!eG>pihkw^wNcItY}A;1XD7f#SJd5bz+C2ai&?JzPv65)JV>y8iUj@P== zD)GN|q)C_v+n3gC63yv+M~)1Q$XaOY4d^nF%1DHhQms`fTGou!wBg#389yfRR~2c! z0`+>pb`{}knCOCGKCRZ1V6tqLiaZW(=Btpr2!cXgVscXAn3bf;j7w1BvV}1DBJQj0 z*%7|GiAgYGat6;+N#V4g89ePLh0}goxl!1`X+M0TPv>brU}Wv>&>k?y?*ShldNdN{ z_kh0~dLOdO?*X68s)dAK>&7ZXv);oa$M-J(5&yx*JJWVd8Tt8$8TuE34{9Ppf3g2E zg3rIE%K)TO_6O9+4?swbz;Wyv(Be4uh2Sr*LqmhVG|F8Kz+cG9 zQ78a^`4N=J2>1(`0Q`ka0RBQI0DmD9fWMFlz+cD&;4fqX@E02K@n<)wiZ+tro{q3TS!(c;kQnfnW=s#i1pI{w8t@m= z2KNFz+Y%`zu+$u5D;@(aZSv{rIZ&4eva(;;4ebbpDeXXNcxktgTGt}eGUGy znKAbV{;~}LWz@SHU%#1jpg$SFUv9vU0e^WN^cRD_@c#=R{DnR!0r<=57+rkum+LUC zG~h4n5C;5(h7I`3BG3l>Wff>2{N+YO^}%0+G~h2krF_5OFApMQf8Z}~B0v8X@E4Zn z3&3B_Lr|3V4fx9kD1ZTf@o52nA#K24u0}rh1O7s%Ap`#M7H9+h!v1BzU)ZAz_zOFd z0e@kyG2k!kCkFh5{Xrjv(s3=@J&r=DMCw4oz_pD1mDSk}{=#86=6r|(8Sodny9VGd zFJN9^z+dtuh;6`M&c{suD}cXT47C9Keff4@de3z+YA( znt;CuK;QnrU-*!12Ylf^aB!>E+9 z30VgGrN3x2QKKc$V2J|omsz4gXV%4^{n{!$0pGT<*$$oy{we_4vc1>i4a0`M0y z_xRv1D_8|S_{$d32K+_pX20MsSb%^(nGgQ*1I9_}w??)HnJvMejLlqLC3*Wr2!FD7 zjga?BgzzVef)-8QCK1A)EJq=qMBLjg!cwioYzYs4GKNV^7RXm}xaG8r&l8r$#AIJT zGsOP^nPxF09R6es6H6?Pjue2uTn>>B{_+{j2>1&tD7Z;D|0Q`ka0RBSeD}cYyasd9) z8_fQ}Uzo{C3`MM*n8Sh@@Rv5w(FQ~m@Rx1Os1N?ap)&w~;rJJTzi`M5z+X5SY6pKA z4FgeH!4ZnMmR*MnzjEt&6iPFt1b^YYNu;)(4{{nLJdZ;85$H1$nO0l_(Ik%K7E!~%CEHsnX^Z#KF5W4RczN$-gi5MeQphfB)6zO z#w;~}h9PFTRaAevzl-{_t3Ox5KL;hOmJ-%MpCzmjy;gAhmav=JjTrw>3737ogtJ(} z9_=M0&l2)?-x5+1E+KhS!V}s{xQh3%Sn>Yz1Fu@#!zEZR*Y~hkO1RT6VNCSC53V0q zGuA_`p0Q$8Sc?MF!1dCBRwHHi!Zl8Kr$Hlzl<{vKMv*p}u%b+*{}?nL`<+KR;^2Ek zQrK^6Sp%f`yu;@BDAF2$x_yV!!47!FNx~hVRR03vFp)=0!je#fRsTB#R3JyMnSeBM zz}2dOANx^|uLAgS9mE)sV$78-$sEl}=J01L^U=SBmGc-&(_1n(7S*FO_ZTzR&*Wzo ztEPCBqNnT6PEQ0<-ZPP54`bq1X+6M_81jBL@ z{Tn?5vH?cs-{?ai6CLywsYcd@RAbbNvc~!kU^U)>_e2*Q?(qWny6S4YgVlH}k{v4O z8+Y)3fD28nu7R4=Dz>S(-B_zXejNs+R*lHis^Lwo8s5|@P!QOLU34g;YV}Vr zTc;usYV<%PivzJX?+&|XG|kS4l1gR{^tXj%q%9e1@$oiOZ)aL4&!^t zt@fjEtKLv9{o1qnujLzH2O=$Zn=ZLLCiwi2s?jc}x}v5b<)ut{DpT$jqsAaY1qqVV`2o$@rMEc-Dr|8UO@S6S9uXYnNSX6mb#lk+hEX?BYKv+@jsa`bb*mDKrBo?I(YB(PxM?oCb!`z^uT) z+s42!8aM+6n7v`l-VbSQ(SGuyt?{%bdm!&yKCm_mLy6ShKwA5?SVM~$$QHx*0Nyu= z(iP0W8pQkiO+=@3SPfF@$CT=VlsITfO8uA;oOW~z>Bknb(N9UDT*#CLBi`R{5|Ywr zAD+m8I>t=YZ)qh4aUY(D3me=ZJcg%|`0zxpfS1v<6BG|gA|9R!bZ_?i8O74i08d0) zW50uYpq57>6Toy8!^8OQ%TKuN^sg~1V zg5RR2Rm-0d&Myx1ZJ`q|zo{Xrg`QUYruwRuS!}HMmLIKJ=qAN)s*h@U1NF{tYLIFn z03pBSt5pmAXZcO_S1o)O<2Ti;TKKNPZ>mAHJco4nO$}AnL)};$9$e`AZ2TJvK%b2% z=#c!}jluF?J{wP=CjRBK;kMS}Src;x;hNxMM=zfF*h}urR){qAQqdsn+d)IxjTutW zU~#7Sm(K=0(Tk6L1x?9^D(dhrpA8=NQ!*p+2ULoNuPK=+OvWnbVLv5@M*iiqQMyc= zOaA4v@h_hZ|B+kDSzak8gm@a?FW3LyeKu~!|1_!L;GG&dnYDysmb5P z3<_@2RGG#<8eMk>ra7rY2S6NmZ^a*LsX3gYC*9qY&nFF^4aygj&bWETT_KbGqD8B5 zf)>e2_k+$5ucJzrqBZMr9@Zw(-HO&9y~au%N4nO%1c|3kWNzwQdZ(whap-KYBFkxi z%xMUSIcMXVxDc08ULX+1j$za|L&!drJA*cK4L>we9XH z4;_X%Px4yWi zc;8beqVs6?6z@jA@_5{lcdIZOsmHrroeDMWp5pyPT>?hCr+5ztquo=yht&i$ZS9`o zJ*L=aw0nvdM(XjNR!=}pyQg^1D4uhp-BY|5BvFmj`OPiT%mGiixj7I9w&LNo+vGCR1Q!;7w?=a%W?kwf}y6!2N9;yuG z_HFc0=YaXT?kSl8>QF@M=w_PKPe2G#Po`P#!z-byS!R^t2A(GdrD@a zdJc5Vc^TKl?{O*R1%lhrT*N&kGgEygDg}7;O?1RXR7%-|w0lZszN&&a=5(dTfIx#K z((Wmlqtr;z7>BF4r_3^1+C3$+MlBJA6;#-c3%@!c{=uYuR2~9_WPSm=`O0kf51}IN zDcK%>V2FD?F4dCGkt&w`ND@kjlp6qJU8mT9HG--|0lU+kv zBlTq0lGaE)*>%4{QM7wX_87`7RmJ0uvKvC~DcMbLQA@k0WH*bNQ^n(svd5BfoGP9O zk=;VZb*gyWQTBK;ai@yM9c51-lXR*o(eJV+l1V#NJnkra5}Axs#p8~$+Z6s?^4(Li zr!b`1shUBx)5;N|-BYrs=Ro`JDcS8q$Y}SJ>=}$=xm7&wD0?Ou$F1UVN7=K;xNa4X zJIbC-Chk`8xTEYh$t2w>9(R;IhfLb7;&DgWon$g#n6>lB=k5u_mu1>J>Qd*uvPfw-q+uUbl4yQgHYmb%gIDcNgi*h*CK zxTEaeQ=#U&r)00af^mHJ6t)MMEx|p7&Ag1!c>6^N_mt<1koQW2a8G&H2zi@C2=^5J z{aD5)QBNcE-BXw?QG$C4!z2wBNQ9-9(@Y_sCoGLGEMs5a5aO9J7DK|}p29G(#Ny~k zfqTlC5Q%$A_ByVsbc}lu^)h7Qp5i%r$|OiVUV$(gsmF^7<6=a>UGoanO^6d^#EwZX zuKMCXSaDCmd6Tusja9f>?x>u{9eG{U``S`>bsR16xFau& z)Z>Mbdb~!NCis?`B@Os$@VFyygc=G19lPMf*)ojk;-2D7@Jsb9niUSIBm%T{Px0mm zquo=y1;S|e6r5SffkY$qcq@d_NIl*fv8>%wyp763GTJ@GJ3-VmQjfPyGFgeCh?Ns_ zSTJ!<@lH{vgN}AWL{#1xYBe)T_Y`l3;?SwxQ@ryO$3N|!;$5T$fYI(L-lZ}b^4(Ls z%T*l=L}?}FY{9i`7cTtDt*3iRPfGbtz5BF`DtBojXX+n)?8dWk^Hukzx-kR${R=i3Sunk zH;(+C_BW3F9vV)%{gG6D&!u>3;@mc9=J)Ic-BN@DR`YwVgy57)9I&d%vu$~=$nUuo z^79=$;PUe$Al*l3WU)+m-1|u%$w`glzDI*ckuGqDQNEUR)Qa#h!2CL9GD-u5-$7uv z{Q2LeF&=xG-z7an-UITx+TR26yV~Ca^1IsK1M<7t-vjcy+TR26yV~Ca^1IsK1M<7t z-vjcyd^hznq#kpa2YC-*A?1-!h;y%;1i0#hkWIUm_p2bHa7c8GxFxkQNjcux_+lQfKjS=q{_qoozNatH<+tgz`}m<8myT^pY5_D<)QhCfb{EUYB>2L%{ao&P@9a zc@``KUq^T>`%T5DYI@&iYH&A@11MScyXwzKq2H$=nd)fwYv|gplRQiH8x!J7x7qzB zhxtWz{aoPjr|HyL>(E!J{VL> zkIuNK_H7Cs&s_#7V6L!auPgXAso<-Ss8sN6Qo;9v9k6J_5tjV}d8qvs{6H+d{!psh z-npcY)b{PVw()F}`rZTccqCi)-D)|UAf&#H%+$BxO??~Q)OW!9^^FBv{gL{91}VrL zeL?+#DX_kc%+$BxO??~Q)OW!9^-Whl`81%9NPWKo)9v*=&}z6J0VSyKk4yk2FmQNs zJ;+k1NnP8#2RoNo{h2^DLMYvUYb(zguzIZIJ@}Ryi_r1lRU2I>dPzNgOX_hpGBW5@ z1U-m=!5g867}hmlSoK%=Rlic-m#gKzoQEh4Tm780`8m;P?p$dN+2QBJ>c1XT-ylzT zCeRIx>ByrRi@MBA(`IIIy>_%igt3y%4-ul9%6e%kH?h8Y{DrD>)Ke7(IBhLFE_7+; zNNL_=)?PyJP$b(Ifl^6ntKkjE#z8hl%OdL^f#RPaWK*AS6s4*6wT9x*7}KEjs(6pl zOnIWZ3o-CCLOos|q&!hl<`Q!MpZf;e?_*!&`e;7C`m1jsuu0+`0q+H!>;4kA84APN z(5k)-l}h}@0ql$~3X82XQUOFHTjFQOLA!r~Y4^vZ2WDb-P z`Ed|K?`)4O&Mhr$CXC;o39}~JGu{sw?=R0({tIg@kc{5~_XVBtgk;=;LLYfzmdaf^ z5WF;|`=HqOEo7RXD86=?`V%tMuQQ%S{7?o5E_wPH9u8dc^fNphxa8S199H@1`*YtQ zmYC?8nMNW*7_a~pV)gxPIJvHBJwp2xhLbC{hf|wLH>VLG4@M(_f7iZ=`yG{Y1o<@Z z$~uxG1cL`-KT87G-mXB3etYXrWwtl)($;j_XSMkApeXBd#D%ym_WLcUebhHv)m@c1 z=S6zw`!b|VIar+I-seE7T1QG%f55S6nW^bV5MvZ;dJ>GVX!b|*A(DzVB2&?ZHx+Go zQ_-jUW$nkR+z5Lv?b%AI(eQAS8*b?KYBUm4jfOYlOPi@iT@lQ+R0Qy(SmqHOSrIRM zP;R-ikfv(8yb9-?NkzQCintNcM=e0EK8A+m>Ni!;s9y!qa|j!5I6aycJujkq&PgE&MnIkyl|Flxwd?hiF3l&F%Lu6#49e{Y5Sb zMYhKDW@&!;4rF>Ra>(m=F4;H7A!wH3_3sR)nngI*#J-s;2k)W?HF(_K!YP}*bNxsu z`K>H@3U^+*6sv4F42vV>I2k5?%D*wIq0oTiOJ!W>3A=uiW0rTWw}y;G5C;Z0`iy3_ z_Pzo^6s&4HCdkEJ=3*o)>6EW!%Jk74{|1yfv|AIzk?$m#mEDDSE%dNEiF2=s;>dRr zA8jo%B@^i+DZk)mP#<*UV*|ihlDvoSt7%AC9Qigd zS;{`@ z4wRQ?`s>UeMeC!%4&8x>dqdWddEb$5ia7EeLF>muiBm4scAK$&1g#%I3#aWTf8wS# zMI8AS(!jZafe6}`ly@NwoDT!c-a=;YK3cnYKl#zt#F1|f@7wgi+A3ph4z0Z+)=-zS zN|?eliuX;T)Pos15Aptf6VWM&Bi{_Bv@A%8eM0g*gDFj?ZMMxBY$4nHlqAYkOlckB z{rx5(DNRV>Ibb((ty6KNnJ9gzk$tFDI(&b2cx$Tf@ApaI?>7Mtz1|^zzn>w|ULk+K zcfrd;go{GcFoSXVkZAY!qgc8l{QYQay7Bir9ZdI-zn^sF3n6Ux_ai59;qOQF={&nh z;q0b+8JA}_fe~5`3qCZ$27p%tE_u!{zJW7NMJ?he(a4Mr5UVl}##>MhTcWq%jPF1v zc`1ndpp!g9MW!47LCz{9Yn)t)|Dc?wL|4HXozPNC&xXNMP_3mWfiTX4a*h(62d5k7 z!R4^CkMrP6-sd*d*I49PwLOjSdY<{n`FHbsAco(Iz)A#)m?usLl0#30_6A5AfJ*G% zicWPe1RRX;$65cEAiD=Le=vasYvyx!aPhbEG}{9?1AjwW`@mF%0mVYE-l5L&k4v zq&ngZ z9NjOxabfKaWL)5l3)|t19RqJ%*bZ-8xc60P3cPXQm%tkrw!<42UX8YgKbMIiRTzdh zE^LQ4F8urO#%}p;SkUmsZaciO+YWE+hTx4gt>KL|t>KL|E%3(fSAaKm+u@Df5WKM) zf;V=DuxJ|I*bTuOyCHaEcNldvysu8ys`V$;f>vPcw;vNZ|rUo%Q*UUF;dX*#%=&_?6$)j zyFU~~!W+9Gcw;vNZ|sKPjolEuu^WOnc0=&SZV2Ak4Z$0`A$Vgq1aIty;Eml7ys;aC zH+Dnt#%>7S*bTuOyCHaEHw16&hTx6e5WKM)f;VueyfM~V39Z^J@WyT!-q;Pp8@pk6V>b+M z?1tfu-7vhdyAQmvyAQmvyAQmvyAQmv`~N(=u^Warc0=&SZW!L!4Z|C|Ukq>ThTx6e z<`BHG8-_P_5B@@UV>bkE?1tfu-7vhd8-_P_!|=v#7~a?o!yCI{cw={wfD3DQV>b+M z>@JZI4R7p*;f?9q=Hhih;Emldys;aGH+IAD#%>ti*bT!QyJ2`^_aBEhc0=&SZW!L! z{p#?>ZV2Ak4Z$0`{}gy*Hw16&hTx5hGPCedYKJ#2YKJ#2`W(D*QQa<%Bs|Vj;Ejvg z;f;&i;f;&i;f;&i;f;&i;f;$w2X7n;!5hch;f>=Vc;k2o-Z;KfVYx)Z8^=TN#_<5& zI37_);SVYQxXRe);f-SM7v4D11MiO| z7j#Bb{Ch~pPr)BU&a?&6F%Nn6k&Y=Aq~i}vIFOECVK@)0ES*fTARW&E`#*zp%(I{c z>G)wL@js4qd?Zp49H`eoNR8mY%BMm9eWYU#JxwDWFJ%L4M>-~JkdBG38z3E%36PG- z1W3nZ0;FRy0n#y<0O^=afOJeIKsqK9ARUtlkdDa&NXKLXq+>Dx(lMC;>6lD_bWFw| z9g{Xl$D|F?F=>NzOxhqFlQu}lqywa5G6B*t8H038dI4t5tlc6f{=jZjrXU^1+mVjr z?MTP*cBJF@%hW~GeUXmiKGHEU)$fHuJJK<6kA0-${{U%_jtO1-w@Am7?icAejQ}9| z;@YVimkM4WAa=4K9d83~kd8?QNXKV@`A3nC+4uHEI_?Q;$#ZatU4qMv_?o`G8?-?> zro6lsnRo_-#`_hDA{f+2$3HbnJgG)23FRyCl>4aj8kKmicPID@X(a|ABnE+mG?)+w ztBr7)5$=O@JlF)U3WDWy@2E4IAxwE^5EA6rpco%xbZ!fDf(#p-3#r5WJ{9OR!Ky(z z{t=|%lPNn6ehU(VbWHT&FF`tHf(GfBv_U#1ZIF&h8>C~J+%MAc5(Gq@6}WcVfJ+50 z5c~$&@sW;&r0ajjRYKDBza8oLF6e8dV*(oQ7wNbS0Ws?R3SYmO7^LF|Au>qE#O?iJ zq~qU0(?>eaKrui%#>w#p>G(dly&0rqb_j!XOv480n7io>(lN1_eWc@u5Yl0iCVuQ5o+>?a24nEk;Z9kboTJ(qAwQHOaDWII-8 zJJK=7+o+R-%pe`V2RcAH{t$nl8KmPz{8Jeq9Y2cI^{;?*{3O%@q~q7Y1W3nZ0;J=M zU^+lLW}n$V((!@#L$cW*9sd~yzAn-+ix40k7h$?fV*|6(AwsEDE<%;b~m>mAw2d5;8qDiG(~F|Aqgv zkdU9#X%4=FY5tRtkf$ImA|dy}fBXL|B;@;%rjLZ&5$`7dOOTMOQI!26A@e;VKtdi& zt$zX%@?@m5e=^tlU=kk26VzZD7jG88UALM9U+A(Jsk$XBuod?e&sNE;+% zshj;GAwLPV015dIjN>CAvpvXc3R?r%%;lYuw_k+V8o>8*5%OM%5L*L=8zFC#2(dMQ zE7UPQiHB67pHJL?q;em_zIr33&t_(*Y7PnE(ly%vV4{rsV($`A9JPM?z*MD>34+a)2|8 zt3g8kchJdIh$u+NcQKxqPXETzQv;=D?vJ`ysgNx~Be`2*b2sMCbJRr*NC9N*>7qrOH@;jawPJ#XMjcu$H8 zA}_&jyyrqrd1|%b*A%=%jb2*t90av(6xe@nvVJz7K}@)Hb{C6JdUl z-S2tut*8)g3eeVwOsU126V*|)`lEM)tg?ffG z^uW6>OzXq_aK0J*g>hV$T&Lk`H7??}XMRsC`Ih$qYnl)DVLD^_~#hq%*fO=Q^tmU|uRv+YbQ^6Oi%MsCFxw)^&f+0 zQ=Km|X{xs0R5u4|ep5~Cx2dv0NmDJhl5CW{xvnSNmD**Eb0Iq>;Cbuot;Q`7Zr?}P z&#K2(1~-AqZ3_ad5qCnCg{=NL5H%p~2nD_jSw99keye*r6j%%ypOF6JsTg-j9#8d= zVmKz~$CD9;A5WOy={g%4SqVjbSA1D;SA0IWD?T6G6~p^?rN&g6Jf6lQRI)N7@)%R# z5MyNKwiw>r7Q>s{67c?Q;pwpQkzq20vO8eam`GiXUj`#HWiY%cgW*jX0^Tpf~A$j(T;u|2(5ay2|m<+6Ug*~ww@Ku=XfC= zoF*%OGwY~t_O&X*T6o4EJPQG|`-M@h+BZ3!c-O|BH5Y%3;u(EBjOgjayEbQbdr&VU zPeCw@(D9WyYsAC-mz)wlWY0wiv=H&OAmT$3@i9hRvv0%(MEsNyFSIKW(j*ZHYphee zP$GVehy#{e>f5qekwaMhcqos@E%|FuLTlt<`*+c2Z7Z!V)a%;)-x`f zli#<&$_(oP=!sD_8Nd4cX&r-Ptn6SVX>QaOCUofM66%C|r)%a=NhpiKMiM$y5}FQH z66ymzNr+8w--H+>2_>y0&DGMcRlTJ?!OlbE6QyDM(uusKc*DP85_wCpG*^(N54HNe zdZrW$cjSTb`+M2o_FHfRmLG$O|J(A?))mk3pzNa$#4TFrSE%?**V1)W{Y?EjNS%X@ zPW@++`V<(DBK}NLUrSa}e?ak_>|5lK`U8^sE#L+m&D0-Me3$zWd{7~yKSm;}_DQ{k zm3*4g?kL-X^OVtxFID!Ee zBhOadl8|Y2q^d&}`fd-&08c)M+RV=2T?mkuI3oc(`M!z!qtkjnaot6((Y3?ZHT{Og zg329)a|P?Bb{6koAB7z%F4_}nY$+y@`VRJy8ru$oy|}#$T3m0r20Ux9PHON$a8iRC z5KU@u87xIu2KikdEOlJ4pEyQBznW zIjIqD+_q{LvRV@gyUXvNBw2Bk?abj#bZH-@o9zKH$2G)cY zT4`3CsB4X8YFJ}`&e-)I;+d}ad~ZRFdOk45FWZEAr`(!&HR47d!`a7Bn6wuWz{uM6 zWbUSj;H2fr+)WX|Zi>m=O%cIvipd7Lda{A8p3L18W!OzInY$^WSPrEV=m z*7?m%v0J~78s|4R*=`*L8Nazh?A8S+5x=?dcI$1B@td1qw?2bkesfdp)=3EGH`i*n z_J9q3b1imje}wa!8)HvB8Zv$l_-iZwqvkg^$!^Wym*3n(yLAhG`OS^9r*Zcazpbai zF2A|4cB|P25r0~>j)08c+-SS?5k%rQH_C3s)X3sDH`2BUuHpzBhQF2Jn|LB}D?>BB z{EWc^&}?OJ3NJ@xM%;p#sLF`zJXVAs6@3Et#TkHm;`E$`7!l<@#=B`3EQs@`@U;>I zO;6x5@fe0X1#=MJ>A}n7Q$wxpa8c*yp}MvS{)8&Dicp@L~;!ZD0E$Db z=Tlr0MJQ$|FIdBOMl-3IIdBCrT=WUc_8_$ajGVA+4_33;ECdzX9wLlJ#kQMNBkII0 zIRows*bB}q#*5c1Tt_G!+DGDVBm0GOHqi3@Owb;uei&FDAGX{QwmiwV{4sO^>C=N% zkH&+a!Ugxz*bQi9j=e@bPh%0t?agYbv|fkcIE71pN3Hp2gw6K362D|bXK0ik$?q9$U%^bUwh) z9b5Gf3>Mb2L&eT`1R8{kj-8p2;%d0)_-sX1;G*Mm)MZf8aMAI(!f3eY_~F86xM+B- zQcc4}!)=v}hKq*VDj5wI9bYJnhKq&|D?>C~bbPTe8ZJ7%L>LVh9bYPphKr6LA&iEL zjvpzEhKr6b6Gk6B43Aiv)^O4B6~YKybbO`I0v8=$CA7dr$5#t2aMAIjg%-GIc%Rac zz(vQ`3a#Oye^FS3n1`bSh{d2h4^`zawG zfQtPr?@sv@xY#dK7g6~Hi8<^;F=s7A(fPRGvG^-U3RZxwSiH=#ACwkb#sebHhAgAu zqDv~&N#MMVxTqclk*E4wmD$CdrVh66>I7&Rq@dc$(U)>Zug73J#Ae@KiIG148J;Ki zP=!&4*&pHOfFznQUz!i3uu~q~9&nab`4ki%!NVyIOI7&ydky}LcnPx8pkf_V$OQ9t z9|U%hWDbyItn3dM@E4?LX0^M6oO~irncGZGsFGw(K2yY~mz+GwoKPq^c~j?vidD$^ z1)-c!CON4d#{^$gzeV6x$R0bJY9m*(rmv-5($74prRYI!&6<9e`i(Dp1vLj5D&9UE zb)4nUsD3V4*Kgcqg@A@&N>3y8&Lplz)~sw5p7+?yxDv??1h3lKpxA9SYr9R#_$gv_ zlf9vBiVdL|H$~r#OC|g~@ZDcU!1oZb$7!&`@)0xJuj$IOec74qvYwYg#xg_4-{{J= zLlg4!h+75BM|E%JZj+>2hZs$g!`XNs)jr0m+N3xjJ&hdHa(_8^KA7cIzX|FX_N~cK zuGzTWQpYQ{QG4gy$}tG~7SiUJ%slR#Tc!7CSE;E5kvs6WvsKvwojGVRJjjqb8}K?c z6S7Nno)HJtxyVP8uj5s!Jk1(6IdAAPs5nnh> zutsvzHNWxq)u@y4%Wq=Br~~oCZ(^dg7CqOIUEKae{jUe2tbAUvx8QRL-d)T@{iRCG z5`H}ZQb*6(9X)4v^qk$%bM^@5>~7C_RMT^IN6*)a9$ie=NlmP#65cM$0TLq z9^Lsio`rhi9=-Mtkn4$i^!isobK)M2s5Qt=ur+84?8KZTt`Sb$W24W-wSd<3>^-{e zHqbJAkDfwhJ$sLyN*d>kbM_u^;KSdu(P;aC+h%9i+B^k%@bBu=*~WiA>z1 zLxj;2_h^$EjXKd2_vlc`ou0TyhvReuNtYA%*c`s0>xp}GoO&>@JU(o>C2V<;ZugWIF?Nb9V3{y#~t^6h-Bhk(!$U( z*7a6oDNTGLOx#!FM<(tilPH#O&MhSz6L-$mW#V2knc_0O3EpkO72Z~j@JS@Y+>Xx43m(IqhjE-5;aV`7CKox`VcUG5hh*2!`70Y2$Lzf zh0I@t$(Njjzo?R*3R77;a?*4w`I#_XilWW8_ ziP&sN4JB zwAh}7##P}&AKqR-56gPxNK#qDuJ;jyaVO#hm*f zir$0^Mi+VYxeK(1SD)yE(&x*53nMQ;mesF59V*n5;3BudQlx>;xm+ePXbhff?o9OI z$WYp{+{ci~$OwuZ_d=8JoS$V zE@*+BJkJmT(A=$+W~O!^o)ZViNif?Yq#x)3US|B;A}s$a;1BHWVQPvfuxzPQBR9fQ zr{R#eFemy9=<-)cx-kK(`Y|Y1VOoGs%;8XyKbkZC^^rCN@XuM*_C`>S^-_)@h^fo5 zUdnMKcqs>?NI5n}cwnlO<2)uK<=BHznX7GzbYeNKK}aW-N+3*K_4}p~{{Mgj!u%+D^d7M@!*51|DEcs!+Q8vCs zwwEr4Zlh|Ybb8u-T~NAODP2J?Q@UCyU0?9MUPT&rnk>b^^yaj`PlQvF!=cavB5RP; zrGKWERmOhLI5IZkwUr6w;ksn0j*`57`>u+a%Izr0uL+XxD9N||P4etXl6*#z|2Y(D zn7nQ`U2kCupV;i4{9xLQTX;c`$|p8&;j@UOo6RRSn@v@3EE=&$f3;a8DepCiQ+Jww zTQEd0P|9iAOnp$RQda6qS<_Yl)9d;N=H&U$<)jF;ryJArl9P!hN|Gg30S)JWjOVy|ggw|_ZG0QjecR?^_Ik*^Qrp~uyy0`;eSRg# z9edo~gZOnsu;vH3u%dhIYSOL9o>ggDGVham!j@J{df!$|Nw^i0H?8=b-eCCYdKCNO z?KUTk{M6#B+W0=wjsK4OAy-1Z+ir9NpT8e`-(9SUJ0xaz(>I^s^WaDJ`VzeVo4!dI z`er}VH_4m6`Fj|`=fLyAjo>bOFXGov^?M^5Mrw1zybxP<6yjVE5~v^Bk04ItPatc& zg_rLz^uY1HUFq|8+Z-c09SWI^cewV>zZeo0+%oNMAn2f$S^w%DUCX5Rtz}BWwM^dB zay3$sPyQ)3)XSySbb&;*os5C7o7CXtQiFq_+P8pOyQRDA+oJZ^4Xuqm}A#sB-Yg>)?SoqwcFo~(1u(G{&+on*Ex1)L$@~(BQZ_H@TQ4G>R^YT{8rxl&C*2ll%fWs zbALWDH_LMiC-<6OCMDh?t~6h%O;qSaf)*{=Jzn1<((T!0PAD%KMdybE3{fFrZ6y9BF@q z`0cH9p8=g3;UbYYMLORvQZ;1O;e5WzgP%E+2S5IvW3lp2^Kth_H5Ru!2_@CG5K=u! z`J>`kxEF?Gg!_~Hk09k-3!NU*5ygxv!+rA%_&@Bu2b3Je^*-9&(=*e%Gd(-AyR$np zJ2Tt6TIEG3qLs7~s{j&WQ9wcnloLoo5|U8D2$`IWMKIz=5FkVp*(8%p&e=vLm}o4p zvH2N{Z4B7J`@UPv7n3pc2iZuCc^9|@omj$w5%m;ih=08=9>@^>G>ygP{wBY)`i)ZT? zsWFQ6@n4VC@D_@prxIfQ{L{u-m#+19;W};}YtDsk=~_>jeyt}T)S)M=;BWWScAR-L z^8W{?ZG^I>uG?x|#4iglIZd>+`}f(b(WPc}pkQ+=!g?Ep^+Z#RmRBx#4mEnvZ9jNk z|BoWiEnahsyd=6Dd|@SkVPi}_;XF*1ZfwExDd!{bvP{}X%Bkw__fjj0*?n*yVxEG9 z?!Pp+n_&fiJs-zY4ga>WmzS7#B7fs=AsdYJ#&?8R>%_7+>gl^mPj^VudxtwPZ}v zr^B*zR#p_R11o*hD;Uk)&Ff%H`Y4bEqdDM%k@TdhrL?&{$luFkH1FnsFSj|61Z@uZ zpv`akZEhO~Qw-aYKy`x&(n{^W8D25_U_66%=a=MWs5Hpr*0=SjQo|9%0`%`;p6dyN zrk7}@yHO}h>LC}g2Vdp7n1AY-i0VV717D??YOF|yaZ0{MHFHw?Za0JX--pV-G`M4>U3P^=Uj+m3w_nIl(Pp?&ymROEc?HRy(H zwLLqIJ28>jvZe^}IbIqI0UOH(M&?MGF>)44jZCvbeEl+t3DYD&=}!}VW89~-Hc*w& zS+X|JB8|5t-$SqMi;Y>MW{FgP-GVM4ZZEk#trddT-%TF@nKKF zkTLE7loPH|H@(pxYM9^W8`%zheh(*c} zv1l107A-@>qGgC!vPm(zk{ z#g1K&tDUBb8(#y>ou-PAITv%?hln{t)QeNjW`T$~`y9ve1R_>(;#Dk<54sg6QO^*F zSjEYteTbOTc?%e|$y71h`~-|_GF8kmrG~P}R590-D#|8P#e7rhD4R?bOH3N`A!5$t zFTup@5LOcjLXfI>2q0pPK*ZE0Q-y{Os~Bot%*(cHGF1!{Mr|@x=;*MD;Zi%b$yBko zNz*<$%+b(c6&gCMV!Up-Q@5<6!zy+|hdCNLtU^PFRctV?VKogwhdCNLtU^PFRh(zC z)72(Zg^muZ(9vNP+vEc5qr>dwGR(NiWd991tWraV#l8g{7W)=-SWM7iHM|6IV@Y<` zvB`8PXc2N_Nrc#Bx(&48$l{CG)q*37FMl3c)h1K?^iQF|O{Vx6qp+&OD5}6xf1!Jb zNme$Q+!^MRP*R&r?o46SCX+i$7`4gd&K5>(GP!evQJYNeTw&BElRHlswaMhp7e;L| zxeJ6*n@sLPVbms*yGR(d$>bg;jM`*!4;MylGP#R|QJYNe5@FOPle<(H*<^B;2`!sU z?sB1JlgV8nv}`iDM+z;QOzujdWs}KWCA8XPa#stZHksU`gpo}qca6|A8tN znNu<9WRofJsf5E*n@ov63!^rf5}yg9HklHi3nQCMi7$j!n@own2%|Qc5`Ps&Z89ak z6h>__CB70yZ89ak7DjC{B@By0M{P1COkva}Q^FEPZ89Z776+2rWJ=hQqBfZlVPVuJ zQz9aaY%(RHLaR-tgd>dFWCGNbL)G78N>p0oFu3aNipRI0TV#`|;yJE(WRt04r;yxa zs(78FRyLU`-lZhT4ug1SFdug)dhL-PWYzVIpyE07sUC4vRG0zs{ z>2?KV-5Kv>If^uTi~{vIRN82^yV-35_@);jcn<`w0PGT0Tdn|j|IVg05K&^z`Org< z7+T(HLszwT4%>SiEcYZd-<-o{zCrf;9@x3Ol^it)%0%;;b9pxY0=5@=Y94c*h$VpP zmHEthK3M6vS`^UxK`6AYI1--%EaS%i9($pd5Ei{eHo^4}TH$LBFCE{kaxS9>qq6`g36! zS|ap-^E}YALL4Upxi$>VqTCoXoASw_0WSZK4RIW(^s$oOp9@m!9I>$%my5t_v!_D0 zKyfgaix4oijSEYkHujnVYxZv?A;d8_xTP!@%=ftVhhoMUvIYtKrKS)01I+W6I%LRk zknoo}*w~J>yKOXg!BMUKZfH_#zm@1s{#`Q^HPnzqR`0=(S_(;IDI}4lA&IO54raPS z{|l1Hnz%$Hg8sMs&k6`AvX-2{1pgxd6-dES>r2c3?0}IBLd`p%7PfE3F>-7Qf@4re zJI``LuX`XpA@j{3TZR0Z3jI%~!o5`3YXr%OR2aGs$=fI$F694EcRwLpNKT(kg$C*_ ze46CGH6T~hZuC`<;YH@zpdH)3db)`#*Ty80uib;>1ZwV})TkVc!(vb|9zy640iwhm z`wD`K+9M-7n(udSWoiD%>Bc6n0qp%cl?&*9hBbvDM^#k`+r6f6VPy; zi!YQukf}JN70EL!7RsViS7Inuyes5&gud^;gN!u=8y;Tk)?YLL5q;}GA z_bKWRC!KWrP-g_`TDKABymD{S8Mi0t4$^t|Me2+s?HRSFA+uvvj{hS|ev&EslQi4~ z%+X2uxO7*_C$P?jnLd!rWHPpCR9 zt{2O&z{yg56$)5fdB^Qxo~xBc<(;BgGiS9?`6E%RLF9qN$x{kK)>}I;o}nxJ|{4s2A06DC7Bdh<;rRWT|18EVqQt{h^qvAMHoZjdT$m}NtrsgWQgd&!mHSFc-`o;lSyP0Ymtec=Vy@6x6a-+p@JI-wQ1NDxzY;c`s!%5_hw_H5%ykRx8Q1cY) zHnjX5tKoi{Kh?@2?L!Nl$KfX(JOJrh2Mc?;>fmM+UqwNZ2VA&ttZ&9?;MmdfP!yb$ z{iwtI98+Z-u;l7J!sL?zF4a(0z1LBok%wHotCs(+xLL0dP zo7T-_F?Q}CGTlv{VF$(BhW}xkHuFcqSfX-ovnSR{xdC$Sg*I}Fc}_+O6UiMf=ib~0 z*5XDb{|!L~zlMbuD-W@TqU&=%Wu6(<*+@5XC)3(YIYD-AC;N7mXgRr?s5aZ;1+*pC z&brN!lR7T<8kxD)3CKSw_cRU6v;K&BPS0gngZcQL3s;8RK}=a7%*x!u%(GCK4Y@j+ zUStuce_ZZCp6tV{L&2Pu+eHJ1OF7$e=TmL5;yK;ra6Vmtr>$u)xS*p}`f*c5&c0Llr zHYFbCpo}~SehWHmb0T`27Qra30Ufq294k3edV-LmEu$&Ie*Mbgb*1TRmj1Q%D(K1~ z(CdU=vr#n?|58Jnk*AiD)FU3q^y#QpYH$+<(M4Q+r1l_rF{PE9$KMaiFpbm{CS7_g zB-O1j)9yB`is5GAf_4kTp=`LbNf*0=w%oC#8<&8#-FJ}H_11uP+~0eko5q2zbZ1cB zJOy;zttH)sb`tIq(k=Z#C*4m;_y54;4ft2gJAf6Afg# zaX+K}V9I;Ar%>MZHRP@C4$6o85p-YIqI@WuGSH}`>hU0@Urns6fQC=>l7$@6@QL0+ zZiH5%&r1-5h=xz>DJ#3jaMr2@-i6%N@)>J#b36{y#F;10Du7fl^W@q5?%Jv0H=@aN zreJv(clnMox#LX8lP)9hC2wRUQeD;pWorHygTzO}R}HC$ov?i)QUwiPwNDQSs^uMJ z^27sJ-ZqT7ka43{i5JFm^8LfoV5ihnAD$_p8a_Qnz>)KJg~^Hfb285(Zy2qXBC9M`0wH+|Qg< zvOHe5+^Jih;9DjPJ~_>N5m|f~eAV2=G$t_kPr-onv4#unLx3m?-8U&jj96Z6hB<8nMkpq z+G`iF=LFSWyZkMX)$-wL?dgoZQiB(cwP*Z@r^Cq03&->!CfP1TwWnv8!=XfGu#uiA zj18vENY4_+0W-u%&lV=$^R4wae;$C}FiQ)4`yG zqlB5+W!Y*Yy+-J{m=Ww<$4)-}2|BZa=dgvpT|a2T^TX8JU?dE4c#jgrs5D>Y z<$D)isbDPOy~yFv?7nizLOh=;1{g^8JQ^H@ec)YgyF>g*agHiZl zsER0|>~6hS<6D9(*o}mpQMdvy%Pq_@5Lxy(5k{2OL14Qdg)b*>q1HNZeOT63Ts8L; z50ZNl=dmYTQ}Vmauzdk0Ot*7b*$XRCS^hzSLN@w^T*yMsgPq>jh?X=E72`vOxjCqq zYRfHtp3Tg22lGh9M2n5#1BBRurdz`tf@X=uhH5ew3cZL z+9O(lwL?_hx=Y<8We60FzQir@XRPebQ+;<=9MxN@pLD^63kJoF6cmQ-jrD*QiZk>o z&J5lL;Sg4Dl)~!8Q&_!N3Ttn)?A{Bgrrv0UeSa3RpE87Z;js2{%RXSUSS)`gXHVQF z5_!2LpUK%vZly%~OfH<64vG3K?hZ_%a5=bESOwSGiFA2w6IQ{sc9B=EF0LV|TwUBv zQn|VilC_KU5nbi#Ld^UU{T}I0sofj1HpDeUbl|=q)xM^)`6AG=uj!n1JxD{osc_Ct zQ!M+M&N)B9U{w2>&W=jR)xM^4iuWna@diF#^Z(>a;6zh;Pbz7Iz2YdW*d9vG^!sBz|)QbXC-bmp2;McLPM=9^MS z+1GTI$Tpt8W{6H6fc!Cg2#yIxL9XH<_;@ZlZ8A8uujvc{;1xx2)!+;@*YRQ|`E-EyaHd4g}5s|IHp zzJ@@4_3>PEu6!0Js|IJKS%Vb$c+S}%-`S&|mDh_Rv&gE!Ia~6}$8*kkCOcj2YdRN5 zE7iwy&Q__I`gqRSX7ZHztA>i@GL*P#s5qJ=W)3fw;`IXins0-akLO~YOs!!J4Qvpm)~Ndd#(Vr|b0>?)$0vj?ViEX) zD?TYCMO2OfJy~eGa@2uf4iv_bUAy=cVdC;>SbVB5NiYM9_(8(dx>uot;?so57C_%oIj#$|hzBqc&v|vxQNcvWYpus7=|#Tw&CvY+{};YEw2bUl_G1 zn^+)>+LTQ!6h>{zCKd^!Hf0ls38OY;6Nd|h|n^+~Z+LTSK7DjE#CXNzDHf0lQgr18l0DHII zb{^-)zOwn~Jm+D&%jToAQ%J6noY#4FWb@H^m%7NxYh=vc7xI|B86tZl4!B3~jduoj_T zi<%Q~;9II-%AX24)xyKs7Ud1R;XVXHF1b}gQ3QjJ%JJGji2>u4l2E=9s~WSPqY}?f z1T#%3F##!`1St(c3WRacqCPYbR#Cl*7i}ar1<6xO$$m-)Q&=*;h5JU0gWQJ(I$KLR zr3wc+o2bM3-dob)>O(A|0^1=CB5vJ^3u^V=FF_K03}jpN{>R`{IQQTbR8LelfuITQyPp(V7x?uwt8qd_0Z;GxUDwMfZTEmYV&0V`bv-W7NPu_39L&T@oPa(B%O5T<5)A9G@45Jfuu9eg`}s@WFBE;K~H6UJtMRfwW%4o z7ZPH2JC2F5I8^Zf!ELCH1Q)BBCnST5)hrj1!NqFN4>yBBC{}t<&uQBS5-2#0C6Y2u>O`Q9-0M6<*(Qwi^ z3#oOR4gg*2n5bXfrs<&DDwfO#c`*`adPkN>tBH?Ob(?OW+-~C6P<5L)TjttLbh%i! z=~kpHw2iu5D5%~t*&pfJ`lR_X>f?qetTlHb175|h?q}3z1#n`6>2K5*go%I|VAMAW zCXJ8>vx2l!Zab|QQ{RC2Nry36;b*nxE?NqE>i#}Y%OG&)q@I|C~@klxs zq^ZMeMy+EB%?m`vIZS9?67r5CG^f6Yh4C`zbBebZkr+yk*{nkidyn1Oybh-r@BVP_ zkSplBXi(it7>t>a`6$xkq~~U@G@nAH<#k;4S~H3PVYux1><#93F?novKF&$@7Qgf8 zHY$6&FqM^yRxU8IcbN=#5qDol#_R*;#bEO8elU}LT$mni6Z1T6?hn~O_Y%}M`@G3H z)8?Mfl%JZd$lC5cg>#vG*?bXd9c~Mrva&xnuZOiUE}z1)Z%Lt@?j(Q^vhT{>VS;-A z^Sm$2ME7%^rQb*sCRHA}=5QnXiFq#!Om)*t`P6&}%yf4%>-L3=nVCl2321!A5er>p zeq>y+P<)Ixo8mdBr&(NxN?XMa6c#E*FwgDcUKoa9qmCGtOs)Ad81ZvAOFN5iLdz)j zLXL{!!|3?RBJYi{;*GFcTP#99UF6V+77-eM+Fy8&5+IA(XJ#^90$TV&L|%3_W%M~lXOI5zOUGCj~T>b_uStTY#j!cr=nh68`9 zAP#PIH+>2eig^Zh^Iop!pP}Nc#(2v0`iLpcjX305N!w00G(NWnX~+2(Vi8X z>00M|tj`siqbN7brb}4ZT0SY+X47_Rt^bf( zX47(-+8}Cn)A39>nv88X4dqby4jIR8`Wbs>Bbm6}#1Fo6$C63fO&;6&T{5+H(|R(; zlgZdkzvp>9(Zt?c-frRpYVIVabl6P?QSFpEq>Qn>#S4twsSTiwaMPb~%$+ujOti^m zmeZL9J`C<av&Ox|fafd;ma@tmgbkvX4Ci__GLYX3u~htss3DHoDyb(#jUIv11a>omQ>l&xe2 zI!zDr9A8SN&1w3A%w=TSou*^hZQCZHaUD+6E~Z>g<~XORnl0T<=0V3>vdG9?aS*$p z!aEZ5m5WHnn$BdAS4rQvP0h@HH4PhyrU@Jx*PaYDJJEC->%8M~=1HmtWR3?}Eg^Uq zhj|UN@$`!j!NcANggjRwMDVcR2ST1E5h8e41au9rM7;xHl`_X_i4uZ`F-^)~gG7kn zVI36mdcxND!Wz!?wHnWgu^Ez%;9*P?OKgtHq;C2l!#)Ed2_BZa?l&-#j%P#WyO6mj z!ARCtOD1;;dLtVa#&!o|5N9L8IJhI=tYxF-50NLrjOk=HZuZ0a!+nr?N&mib1kPHv zRv6pmyYy^EZZeKLgDG7kC2rImNpmgcAC#q@<}tK%5%u@*EpdN0+t0W31(`vzOz)8`ag{gM&#A{^nk_(n=-K(j#&SaFzj9bTg9V=>iw~Z+$N+mtqir6_Z zn+>b`3F~;0c`E2gBQm1%PB&Muq6{9E-E8vKX}FcBVfF_m?|-)2iBX=t&>RfLamQlJ zW-pP&5IXNNtkklXnGEU~p_Q2Z9UN=6;J}}p`VgeODdjT(*G(d|)OwK1AmO9Xx*F#o zX8#Vy6oZFlhgiJ7tEYp8iJw5VcpjeHjN%74A_fl%$J4=7{A-x<5>i9Yk(}<}*humM zyWz5R_%BZf4VUl7yz+F=u)X|r(6F6`lg?f^Hf+BHJy+}0LbGA}wV*rsbkMMUA_OP# z=|GWZTJj9guzfD%=h?UzHO#pg1v&H;-mpLxC(fg!59b2Jc0QrOBS?px5tOeY9l`r* zN*v&* zUR4+c3DB`Pn9l_cfsVx?s?x8sE<;sGr;r{-+HnYUEVh%5I|Mowhm%e^1UeQ+kgjzI zbS&;oI^z)NSnMF3cV48O_FDxhO=*2%OdT{fE}zPx3&IV{z72y`sYW1wQkVFilw+3?fQ zIW$#sF%JCsHe>eXV7f&G=vZ9)1Q>@v$KpDY*jB(vE3OyIu)v`Z6`*7B4u+bm0MM~` zr)X9H=ve%bC{_UISiFm*UTN>Iu>8whygsw zA<(h-RyvPoM2A4f;=7+iKHVYEvABzKVx~i&WAQ!aU1&7$AJwbmz(!TsI2Tovqc=Sy zMVQoG0Ue7&EH>69(6Km7IjwOCbS!pQjLm4f1UmYR;}YoTGjVq$`*4)xNxB3&7Drnl z52xAXvY@!Hr1W(ObS#dwGDsQd66jdmPg2@k0v(I{TRoA|?h@!&oM3T2cDMvO7AK0@ z7?(iD;v`8K=Mv~xoNVohJe@9qj>V~>HpwN>v3QWh)=qT^bS!SL_%*`x9vs8PjTXo4 zII{TiGvEVw*9t1iTkGDEt?+vR*3pG!%-ba_bWAz}=v3RQ0i8KHmV>XAMbTG$+ z*1>$y9dt0gXEdCO^TM&B=};8tY@`lP2**%a2PJHSKrVh9Au?TXd*lq@hrz<*I!a(; zvC(`E4TuY{vDn3=6Dz?X7rP1#@E4oX&15mQOJHNMyU8=^pcu9UE`g23#ggYr zm%zs25@Bv|32ZDb73OxAz(%~mV4?T9pRx(dgn85@u(7yYtUYVg@IJ#Lr9-lcXQ{$R z6@N*<*Bj}Ni>s}Nz`F!C7S{@m?x)Rl)=!YI!KmSdgrwLg7&Yza6OLz}@A+}@V3}^c zIFpMjES`{F1U44eTP#bJTI2aSGDg?)kq8f|kR&+gWaL3m1Rb+E@e-T{!6@BV#Dj3G z;YgVYLW;JG6oHM!uPk0iQUo>@zqT4cS6_~+RpSEA!0MwwdOf)ato{zkUR*9zuOQj` zOGtZffjzTFI8-~>@MPoj$3X!pBXT3?*6X2c4x~67y00BUUysMK!W_%@DdEuV5JP@rJzEdWx}Cnp|Zz&lq5{00}PGR=eua2Il~Nxrjt8^+#+zT z;PyO&Rh?)qZVtY}`U2VeO8lCMCKsiLw&7E)ThZdBP{G(W5Q6h0==6V7lO@wue}+K} zbgI5*_W!lUCr-5b|6b?kTLZoVe+-PvU%wsT(0m6a!o{QcK1;Y)lO;W?|8p8&1-IjG zYkUH3$5}#PBe7PMaCT6_K&EuBL~_5%9=j4n4n3cGukpN_lZPJ3Q}T0R4jj6b zDX%}plqtrrE1C4%F4S$D*!l{o?Vo}raXWsfuC>M)WKIr;2I7Pbl9;_lyWK^pyc(z^ zMP;N?39WtFG=|stI?`ef<4{y4C>4zO;f7}zBciZi-h*|xGhS-&1N7pMlSN4K&uGow zM-k+74{u)SAz%`t^a#oCK(W0Kis*|I zZ~|0OCAe0cj0(~F%)o(28m7*Tc%zBgoKkYF5g&CD9!?W*B0lP7BqiXBVpJ=h3={B0u~!hQD27|!VBZ(T zE>zPP&C!q1?aT#ZZsl+p!2Y=!^&e0J;$skF&W8f7phmQtFC9J9*E<-*K0)%njmXfC z(}WV4I$h11P^3(iKo(4ufDfihiT9_WL?rnY%7z|{A!GI48mU!RbZ9!i?31hR+ z52@YyV&KaVFWyaLj9r$&LI%HvyT*3MdF9U=Fm@-#3x7>r$1!*wf0=pK*uOxLzlJ-< z9*N5ae+{>fr573g8tyPoMjqQZt0#^Mb2k_LLd;!X_CEeD*at5vG|Zj#Z(#01{|Ivz z`Wwt$=x;E0p^4j2JkUuc*Yu&k!Q9#3z}(qo%$@xW%$@xW%$?nS4a^JXF5HWk2Ep8g zdkeXdCHL7yDR*wed+sDj%w4!YrDe=rM8n)g%b2^UhPjJsn7gQkxr=I;yJ!h>7u^kW z7x^aUE}~)XqGiloRKwgwPu4JZ5e;(})i8Ha9dj3*YnCy0Q5|y^-3@aW`KOq>h=#d~ zYM8sIj=78Kn7gQsxr^$UyXbD1yNHIli)xs=sE)ad>X^Hzj=78OhPjJqn7gQkxr^?G zxr;0+WA36F<}RvZ?xH&8E~;bhqT6)Lom0l#Ie&w>L!_y6p8ij=78Jn7i0+n7dejxr>!CcQFlf7t=9!F&%Rk z(=m539dj4cF?X@uFn6(U!`#Kon7g=!xr>)Dck$gYcW{JK!rZ|TN*QwpM<`@Uj!?*y z9HEd=m^(N^AyaaMLZ;*hg-pp23Yn546fz}8C}c{GP{@=Vp^#CSJ2*liQ*wktrsN2P zOvw=nnZOYW>A(>R>A(>R>A(>R>A(>R>A(>R>5?N9G9^bSWCBMhr03$v>jV6+x1(ju zU9^n3i*_d zr8LZ4O2gcxG|XK}!`!7b%w0;u+@;ExyOf5xOKF(9l!m!WX_&i|hPg}Wn7h=sV(wC9 z%w4LCxvSPNchzOgUA2a}tJW}g)f(omTEpB`YnZ!g4RcqmVeYDR%w6@jV(zNTn7isS z=B~!a+|`sYcQqR3u13e))%;`3U9FC}OaD{MUAm09OY4}sbQyD()-ZQz4Re>)Fn4JU zbC)h-?$TwtmU7e1(OP4WsX$^Ci)-ZQz4Re>)Fn4JUbC=dIcj;B-{k!z4^8Q_V zReAp|{hwg&>UGRrM#J1?bj)2w$J}Lf%w0yu++}pkT}H>;WpvD4M#tP`bj)2w$J}Lf z%w0yu++}pkT}H>;WpvD4M#tP`bj)2w$J}Lh!`#*Dn7jIa7jp;9XBl$`PY1*n{=1kv z06oi?yZZkOb5|c=?&>wnU44f@6%^*KemBfr{Wmdp_1})U1OD_|Fn9Iein*)*Hq2f9 zzmK`gmN9o(4Re>(Fn3uEbC=aHciFxl;ohjQXju(&mmNU4!rWzb%w5*U+-1v{yR3$} z%W9artcJPEYM8sMhPlgXn7gcoxy$O9yR477%a$>BSq*cS)i8J2NvyZR++{V)U3QAr zP7QOH)i8Hi9dnm0WA3tL%w1N)++{V)T~@=~Wi`xQR>Rz7HOyUB!`x*x%w1N)++{V) zT~@=~Wi`xQR>Rz7HOyUhC7Y`-ciB~>73MChVeYa=QEn*AT~^23Wp&J5R>$0Bb z$J}Lg%w1N;++}slT~^230kMN^As=&>)iHNj4Re>(F?U%VbC=aIcUc{Cm(?+MSsini z)iHNj9dnmGhyCGW?y^51<74i!I_55`WA3s#<}Rya?y@@OE~{hivO4B2t7Go6I_55` zWA3sV<}RyY?y@@OE~{hivO4B2t7Go6|6jt~Wqr&YkoG0aT}H>;WpvD4W;e`TW;e`T zM#J1?bj%%4=Y%XN%w0yu++}vd++_mHT}H#)WpvD4M#tP`bj+O(9tQx8n7d4Xxyxvn zyNr&x13J8nxy$I7yNr&x%jlT9jE=bj^1F<=%jlT9jE=d>{6oxLW;e`TM#J1?bj)2w z$J}Lf%w1+T%w6Wcg}KYgxyzL?cR3Anm(wtJISq4{(=d0rGUhH< z#@s2=$K2)0n7dpVbC=UFcR3Anm(wtJIURGC`zGctSH|4sG|XL2!`$UG%w0~y+~qXP zT~5Q?gG|XM@-^1KB{9VjlzKprcmoax%fVs<;F?abg<}Uw_Fn9Sf<}R;c z?(#b3E?>sn<-du!E7Wbn{8yN}LK$;cC}Zvl8s<*X3UjAug}GC-VD1Y40_Ltz#@rP& z%w0jl+!cml3k_=_V(tnW=B}V&?g|>_uApJ=3L56Fusi0iP{!O9G|XK=!`u~g%w6GI zFn5JA=B}V&?g|>_uApJ=3jaFhu29C@6*SCU;qPGX3MI^4p^UjJlreV&4Rcq}Fn0wF zb63zXcLfb|SI{tb1r2jo&@gue4Rcq}Fn0wFb63zXcLfb|SI{tb1r2jo&@gue4Rcq} zFn0wFb63zXcLfb|SNIPxcLfb|SI{wc1s!weGYWI(GYWH8&@p!f9dlREF?R(Wb63zY zcLg1DSI{wc1s!u&&@p!f9dlREF?R(Wb63zYcZJ=$N~Lj=3x7n7e|Gxhv?HyMm6nE9jWJf{wW>=$N~Lj=3xR z=a{>KhPf-~n7hKij=3vnn7e|8xhwqNg1IYbn7e|8xhs}2ca3GtU1J$@*QhXe#5b62 z(}5u39=y4gUi?}G2Gm9v(33z=>>BkRM&O$N$7Z~P#gh`sy`eh)S3fX|gi#EW)5={-P zp^Yj0__HtYMN?_)Q{*=W-G|y94q(Mm$gme+Q)_XYY;C~tKy$D$_#HpFoOHA#wIS<5 zq^(BQD@s|7LBM@EZ1#gC8O(*HX~rO6z9jL@-4oeLqwOXn9t&$Ii6|#zV;orqd1cjm z@-tB&&YWJ-v#jwRTP17bN_7&Bg~<;Mm5Qc>MB#C=WnRAPU_K@b9wy2}Frr zhKHt*!lT&lc%Wb9$|yVl2jAD%g&#C&*nB`k}Bs;eeReD7PhpN;yA|e?^QZ7G@DUy)l1*69 zD0bNclwI}!WpAXapi%6y2PnJj0V>>=O;jGB_6HewfVvE{?*Zx-kbwuN9L2r|s2m1w z-~p-%^1uTWKC1{kKoP#?N4AL$xeoG}-GQS-wu$a@FUY_H)H|Sk4^Y$#JV255Bilqf ze+#DM0g4_Y0uNA9!@vWSR59=XC3OruK+%{V*(N%<4f$jC2pkjp;ZVgx5ZNX=Z5p_e z2dJyS1RkIs;D`!5K#?hVfLaOAMacscYgh6BMbmy{o9K*NnDQvgf(NKiN|wi)n&nPm ze9IF|W!d)twFt$;4Z9cqMdyA=V}S>#3`BtkD1I7_x+xD(U6>{C0LA=)2Pk%W$paKy zS@HnIij_P-@s#4^f}9hK?h0R3q-?k>D4BFp)j`lb9^rozepH(q}mTfTr5o7y%_b4Zxtr#7ST)b zON6O)@53j3@k@otxc6|>TxRV;-{;-o=8*0G$cglTgZFy(47-R`cW>1!mV!|h6I*9tSneS^#nF+I-ZM?3NB zBxRC2fph$NVWzqs3%x;@>F)bfyHQNfbeFR|H%ZD|H$>)UVHUa{Q|%Tpz1Y1Z4CaTD zva)hCU3}dt%o_J-R`fPe+u;5Wn|-^a9Ow2%x5V!d<|KC~`}$5{PIKj=@FQW)H0q|Z z-FI2f@TAd;*e`j~{_9@EjzcLa4#BTM$Ye_x;g3K|XeW0OuQd|d$zA?Av;r?;{V{-) z7csgbLdC_?D!ho14ZMiasVAAi2E2%oDR~hiQ}QB4rsPG8Ov#HFnUWVVG9@o!WJ+Gd z$S6b;yoix0c@ZO1@*+m2`W{vF###Vf|P|p3WNs*!V?2w71gVFdq(ooAo-F~vY&D~ zQ&{ptrIb>QgWOjHI`5TqN)--to}dovYva18T8!M!tyL`%0+nm6>H|i=fO4%>J%I%(*ILyRNh{Y{)ssmp*ILyFl2)#@s;AJT za;;T8mE*}XY`WH}9(f)T;N%F$#8o&{@c=;z|LiMqMXjDEBwcG&FBg)owQA1enk?_s zT=XFn=~}Dis)v|UTx-?rkV~6kKZo|!T>mT*Qq+sGrCfBtu>)Oe0p{~(h}FmQ>FNEE z{C8Yy*>tUyo>_xb`y7(<#)0%*Yo(8Q5sZ91pFZ{vsIU5XKD~((Lb=vTZ=zx4S}VQj zdRS1dwbGmJ1TC($(wjaXnTx$X5GaLeOtp%8mPY*T#^C7KVYo%BI4*K$$ zetMP6C~>WoUX{e)P_DJos|JBquC>yuCW2P3wbH9Nqm*l{^eRpy#Rh*II!2 zbgx2Bwm=y$pGBaRYc0Th-o(gNuC@Lt%;%R-Q?9iD^Z6W%a;*iJ4;kfJ3oxG@Fs)o` z0p`Owqg-nN=EMF{uC)O3>4T36m1`})d@Ar&g>tR+ufu%U1m#)_FrO?8DA!tm`80x2 zuC@L-%!d~Kb=O*e`3yh?9VYrBEEx>$ciOK@1 z92KZkaR@2bT7da{S2Rwh#+H%>TcliT0p@eLXk3G1LnX%Voq?8etp%9R!=msc72d~z zKdFnlyT~o(DcD2RdLk+BWqTfk?@`6I)_)V`W7D-(cF>2a%%M-QOuE+kZ^C?Ry4K2$ zor|*2&d%Z3u@cu>|4o>WP1jo4>GXpkuC=nWy5dt+ajo_Lewfc7G)1}A`UcF0j}N|U zt?c^o)Kads{;M#bIVk7v!+h2tWsJDi%AR^OXhXTy%AR&18Rc5*|2&w_O=z6&S}S`w z8Q-;5b~~8|#kE%Uird%);#wNc}5nf0kuSBN@!YXBs)e@z>jWE-s z3^quFRYv$y3VA(YYkXmfbNwZa{|J?4GbDYJ5oVft@C}4j>ZTtu!oP;dZpGp+d)+vg zNyh>6>A>fT?nyB6Z@_%2kSD^7=_Fu2XVC&(YXRn??kjYy1(*++63mA;8RZZQFdwG) zuC)O3nXD}JG+(17y4C{BM_Hn4Ex>$~CA!uE%!kVa-;%nKm0>>g;hAm$%x4uA8RA;& zn=qfrxJ)b8T7dbGQLeQB^C6>LYyDH04=pR#T7dbi2cukTeG}%xN_w~zv2$WJ8z!!` z0P}edbmUlMMCYAuKFf;IwH9DLymczqT7dcR{-<1P0p`P7rgE(Xm=702Xfj=E0p_zA z|01*!vtPwA^#>gIlkq^;TBlRWwJg_7B88_0-YvNd5}vNLY^i4_jx}_x1(*--?>7B7 z<(k`}8M8;>D1Mymd^7IBf+?{X(zBtADS;m+K5Et54OgEAb@AiWaP2IT^yAd9gHj{4 z0EY`e`IUrwtSjyYD}J0Bu4+Z9^5fKS-4clLV*3GRzMffZ#`0{qxgW@w%?E#*ew^}k z+mJ_LO7eRS$Ra`cTiI5XE^K! zfm9d;i65u@;D=cd{W#@^s7lk1Q+}u_iGG~&!$>PkNxq%5^5c{rPFneK%8wwe{5a+J zCawH9%+iljet(k6k5j&rwDRMWpTIgB%8yfiG8t?*$Uvxu zk~E~`$0obpeM1g-oy<)2;zTKRFxKl5GC z%8yh2dD>KdoboTQX3CFK{zckXew^|zoeX{D$0@&a3uxuXDgO%dDnCy7pHpA?amv3w z7AHjcamv5-4%)5!IOX4c6msRqDZh(zLiusZzsJ1rj(|We zejFh(U2rYt47e)bai5?cr+lM%0UDtEIOV&T^vooFobp|TR(_oF-Aopv{5a*in>?fR z+lHz9QU}W%Xn0_&Th}DL!7C%n; z8RFeY`Ekn6loO)-IOS)Fmh$72pKbAisr)$Q=g3J^ew^|;rX)Yl`ULetm$BsAE*4`QjYTDlwT})lpm-35@D1dr~Fc3 zlpm-35yB`xPWffRC_hg5W>EA0S9{ZMr3c$y;q~+<_wC%q0fMb=zS;!8&1H}VmQ=30)Cwac7xz(KGcUpTPYy8 z&fKU3Lm_D0NkPV%+0AfzpbT^C3oy6GQHu~cEMrm6oYZG267T5(fW$@+w}LSGPNd;` zO)8w()o@;vtP8O?>9>#u?-j4A+kv9!KY#6EA zxCiZ4S=fnm2Az#l|7a6b*7Y;YH%)fIPocBdy8edwzOaKoLS<~|;$m!=Z<~w>-bS}k zA49M0FGviHK+2F4A&NlFrrNva;A-%RAlv)qJ81_{IVfCP9O@=vqT?GNL4 z9a_t8{LG)3gNHz2FQi6j_EYmOG&2dZo-ot44+xwCzx4K?^v})VGm$a|{4F%|rMVY+ zrfnHylb}6o)oX5G)x93Ys(K6jq_DRL&falzpU5U1hxND`Tg-qGg=) z5PIxh>kPB6khmD!M+=^CpSAesbnBSEvdd~jYO*@Yt`Zpg{grt>XS+?-YrGUH{MdaN z9Kf_B=UxChg`_(SWB;pY@l~@k$02!_*;z{)H<<@q&HtCRqG+rE(X$+b6F9;svMIXU zn7D*W7lk;`Cas&d4D>FfjF$#pgfuuZyAx^VxfF*ukW|{aOgr$q%zYk{jEMtCpBdty zQI^i+t2U*LsfWMGe?Xdf62&3bL#3TmwseZToSU)-B-Zj!Xe!TS2P!)dIn1r}{M4rt ztPG;5?4LE@+9dIDCLUKxWY69Ju0s-AV6bg7M3eT$ytx(f9*~RV3`jkO>PjP&moHFR->O*j-2% z))mCCemIPni{eC{>F~LO4uOrm!0kO7ggIp}ONe7k;t|m>`%$*BMJm8+)E4+0v7HqBv(CQ`PNe)VBtN*EFoZF`O-7Y$bSL> ziwv9xQbE9?o9_TE5U}W3kAqYYu;|$Yj423M^qgVnas>g4?%>9xf`CPDBnFE?0O646 z$GD045U|LQ2O*Ey({L0BSY)4{fK(8$=!u_#76@4MBQYi!6DHpIExAb28Tqfoq~YDArVdc5U|LM$C<)Y zlY~Pe2YHlbgbprSM(E(OWaDYQ1n-g6@ zz#@x=P)i_Sa7e`b0s(_VB6hlhfWaXVTd5#ma7e_8DF|3}o5@q=L%^KnG6D$!bJS;` z_h14#@(rfl3zvK6e4+sZU>KE&7plGn2OkIqw?)5!Sb$)aozzIZfWv!%8g~4D23mk% zl@lnI^sw!l0TAp@OeYYmaw5g)4BQqi13}mn+!lQSb1GCI+!m2hp#tHyh>Rnl0^zoZ zj0zP9w?$-Bs6eo$IiC4Q~m7N`PO$Zi$(ncr7n=K*o8`6AYZYIgi(;M*u}yq$X9Hu zFbeV&yF?fT`HEdCjDmc{E)(dIf_%lcNs5Ae#V!{{LB3+!t((xf3i1`ZLQ)juD|V$Y z3i1`ZN*D$Cid`+H733>+jie~ZSL|A06yz(mLrg2kSL`}TQIN0L^};B~SL_C16yz&* zqnK8Zuh>nJq99+fn}t!3uh=bOT0y>IKa>;&`HI~tjDmc{ZWA>H`HI~xDGKrxyF(ZS z`HI~sjDmc{ek6srd6vnGOcoM8VB}_}@6qzCV8hA#SR(BqzW$amD`nn&}+H=ATbnl|t^TM>bJDKu=Fzs#yQ(hFN!+n*^PlOrc z{)uWo6=s~9(;3Zwj-W?Fk!nA6-@?A~7rbEbPFnO(x1?XDy9o-pUR-y`$BFc-MDllhe}TaCJ# zY5UjKDG>~fJp7y46&M;kHIqVW`g3SZ7Fxv=g?}?9sF8U_pFu=C z$`v#q{F{*#G$8z&b%l~b1H!)ktz8%BUAEkMyBN7jEq79 zx(lV8l7BO%l>D2KDfu@eQ}S;{rsUs@Ov%3)nZUmp>A=4k>A=4k>A=4k>A=4k>A=4k z>5_jlG9~|JWCH(Yq~~Hm!QM^JP5jCHA@1O~4D>S+pUVA&On)QsXJKr2dJzkc&xCQ@ zxdkwv3lrzKNqix6vT~oXVE!UZt$QQ2{whqyy^YM5!sOlK8^L@fj8{2&!c-&iwJQF_mMO5*B8hyOHHY zgz2oDh=i!nlia(R#SvzzdoZ;sEZ!}r8+EJM&`Rqn3@-Y8`vl!0D9Pw^1SbkgGP+Yp zq9miQbJPk-GWsrc(WP99#_V~J$Lu6-`r)r24^Wa75D+B^zi(Xsr23-&dqY-6NqXRX zl;kLo0ZMW;Xdfjx83p(#NlF8hBx_PaNgj)Yn0+FSiOo1v@c_YK{1cSqhadu!B+A4{!&s~5!CK@q98xwmw6gfg#K)Sc z0(5|qq+BqEqd~~Zwo0f0Fam>IZpG|gfzslVl2E>q)WM!eC7zwrN=i&X_BBDuB|!>= zn*-r}fv}3|Ra_e*`HCR<FKkl2p$;3_!X&N|FTzC`r-*N|JPdk|Z6VBxy20NwN-J zfRcO;2{HR6920NhP{jiT zFjVq(?TpD(ON08fnp^|=9$p5AEwIW{W zA_6efQtX?7VEw5f$WR1bZGot0E=BIT>2p9g^0~-pl%T7PD(I>pL+fUCAXSi|b@SGO z^av7V(A6)&_(4}aY{UjZS9uW#g09kV5Oj4H&P)(=^&`-J(A93pIYF0s4 z2UBi0tDvi#HgoOf?R%iMn+T5xkf8{=$}u28SLflCb`W%xT~P|U%5z%^x=N-Lbd^jg z=qlS&3cAX%<0C`ii>m^rBeWj`U0n*@An2-3OVCx)LD1C()YA{TDpwId=<0r$5JAw@ z6`+HltEYhug0Au^5(Hi4#Ulv1$}2?>bd}eJAm}Qu0SXyfw~BKe$WVq(iP@}!d^yDK z?84_xL56Zk7PFT_B?!7Y5$UC%t5a*xlSGCh=<2zk6*3e-S1a?Vdk}P0b>0rD-ENX8 z1zk--trT>%8<_kw{^&{Y;%3cAWM zQVP0CrWACQO(+Fj-4_N*L03D$l!C5u%#?$!(n5>O4+LGMg~rEt*J+fXtBngCTrL_r za77F?MsP#08~4J1DFZN5Hdzv|PLZcu<8#kdmvr&SsHqOOd3^n$^DYqLX=xXB;s7E>I>btNZL088ke-Lza z0NPOsy2=}ij||Q1V|IgDgt|e{)x$w!q~Ms?fI}4z5RArf34*RNnjgaZQe|79QpF); z1VLAC5RF@@@o-6lEh+_FeO@$n;@B`6jrnDuRSLTLktqC$3N?T@@h5drcT}FNs+~BX zBGaJ5psOc9#Sgm5YiAI2m2?nvm2?nvm2?nvm2?nvm2?nvm2?nvm2@7Tx#INY24zte z${hMB%Tz&EneGQb9Zot3x=K0-x=K0-x=K0-x=K0-x=K0-x=I>ls-UaiS7mlC1)#?d zy2^CF%!#CfpsS>VpsS>VpsS>VpsS>VpsS>VpsS=&=82f*x#=d#>Z*dS9*E6GKj2Je20u;qlWa4(S3c5-rX*bho?z?1a?Pe8pl}yHN{yiph?!+@uPTp>&qQ2QrjtVu{UBnbb`muVd2? z2{JTy-CCHDpsPeK2{IHxS7pf*1YIRl3c5Du3kz@U!fEPT~)2}gRXAEt)Ucjl}stt!1XBvS zO0`nZRaVl&t%#iyv)Qm9=xR0S$aOeK(ACdD1VLAM>nsIb<^8V|bd|TvQqWZ{hJ0jb z_A>KcnxmDN9mY~7<>A1eoO&Wd??hUPYgw+FL<%$#@0MH!2~T8bKdI-@I0`ZpL05Ty z?{-#q)M7N0y9_xM>W$~(*~94m3p{I>M)a2MBf(lA47(>38+x1zo#<7}lQ(vN?r|?@ zmJP`@)L1|(f|_~~L=|6LR8i5W{WVM#`n&`>X5WsZfKrRiyF~CC9D6djsDM%%Ter|4 zL8*+Qy?`{M13fKnT;4U;4&wQ&cfMv9L+9iaUF$vcf#%mXW+)J6@I z+IU?GVjq;+cs;WSD7EqC*Q82(&my2yukIR{RG?IE&(~>-2urUYNdcvL8YorK3Y4m7 z1xi)4fKt5yzd%lcQcuJG)Ui1H9zUrt3KCGNH+U&tBMB(g(?F@721@mYwW53lO7%2Q zs;7ZcJq?uVX`ob31EqQ+X~#1>6 zGiKL<>7{~;dTWP*5m2hPj-&#mdL>XQhk^p7dUq`Kc&=6&-kqXJP^wo3rFt4D)w_EY z@~PmW-aVvMa8d8xG|Et*R8Iq?dXKQ-3Y6+S_E;0TM1qTYPkaDcfl|Gv-Dch}8C=wR zraNc_O7)(nO$AEzUSQ1>DAm(IsoqO_Kwp7Uy`95BD^RNU3iB#Zs;7Zcz1Kg&09K$> z@2%6&ZUsv9-d%^$xPwS_Mk=Hds@kHocW&*xP7v z+>SF_8C=vm*5b(QG+P;5)H~j~4T^7Atqd;eonjq=mcL`QGPtOBszuK{A2PToho4*) zIVQ9YmJ1~3A9S8UQo|QGcN{C44n@I9_=q~x=NKyMAa@M}a`EE`k?Dfl0B67f0gvk_ zL8)G&*@1zhK&f6Ab2HKfl>n<*zmfl|F$qNPBo z-fW8(Oa)5ybWo}{S5U1gxTrVJx(FpHP^vfI;*eLMRBwSW3Y6+C6h?tky+zi?sLgQ_ zT+}Ma#Ufl|FAgi)YWZ<#O(lk|pA2|{QoYsIK=1-e_0|flK&jq3YYY+qO67%wq}Tu`m7U7*?DKnk>>VuA ztq*6ix5DBH>GJ`H?0So3sZvh~a%7C2=OZy@Qf%Iwo^s@V@QV;u3`Z!N^MLz#*7Hd*z;Ic z;4~(x3iRFD6M~`UmuNZv4#UsfN(Yqv9>huqDGn^3(E(U$dpr1cvxX%dJYeO#g@!rY zWQpcM16SiUv^heoTn}AiP?+T~7$UA*_?cTLb;H#SV8MFH@<|64a!hpaOCo9Tdc!QJ zH7>MOS|!qYBCQQ+Et2LKLzwATsPhOU3%e{S5fZI))(p!-@#o5-*>@;Bm7TL@D15W^0}jq*H+;-&*tqrq zj8q+g{GSB*ZRF?vIV$jt{Owmk*L?e0d4)#a^^Lqjd2Ez2A}RZTff3fTV>A-Y`$+Py-2}IF z1o~;@R3<#k&E&(NKJr6%K=NBi_Ti>L1*Yr1e1*^j%s$`2ArHyei$L(N4JqdK(bs_; z%86}^n-0l7r-Hvkcw;|GxnXaNU&&gXZJq~af2sZ1tbHeIel~>%OvJ%Fm(@OC6G`y^ zKj9Q6-AjJEn4EY(RZlQCDEl#+jh=KO(@)^LJd=fW9t}?VaBs$EG*_}D{^45y^ye#3 zk&1l+OGf(;+FQhAm_l+r_{kHQZxQp|f|5q8I1=OgaI%p}Kd>kNz}E5?SU5%@rl91X zhWrPvS%P-;BWX^W@*0ixdz7h@C*Mz*FoKK3#}#-oX`fCh#xIs&V&vkIk-Tms?;Gh9 zbuwed;4t+Kj6G+Dpw&V@McP3(qf!u@69U}xNh}handVl|2fqjHccH)xMv7ayG zX+)TH`jL1tCb@Y5AQS9;j2H}cy|zv3jKL(FI@SGE_JKwR^4;XE#LS)IG&wnN2tH@^K_^` zYgRer1EKz4=UEE%2Rl!xp>OBe5$X?io>E8O&Qpi_v+hH4LjNq(pEZ_61w#G7&XYm# zd^=Bmi7VN85|r#b8P}&|=h+eJ4|bk(T#Fml?;#xug!+S>XDQSlHl7Sim&{hn6ACWL^)}MeQ zfiP{63x5xeHq06(XSHOQMd%x5?S)XuFpHpMm_<-B%pxcmW)YMOvj|FtSp+4+EP|3@ z7D34{i=bqfMNl%#A}ASV5tIzG2ug-o1SP{P0^cx;v~QS2+BeK1?Hgv1_6@U0`-WMh zONLnlCBrNN-!O}G3uZR#T^b;rjL!57kZ82-86XL%4Ul*hdj?39MONM;{V;7;fMuV9 zLz!}Z0m;x7(4GMjFU%xE0^SW?4kkLd#bD#fTYxNvX{&ndX^`3gsp`egL5l%W)qWb- zhyha7OXO+;q^g%$6UVR^rmgBJ1IqAal`5-osNw;PM<8Dl!N!xTfyDp`8&8tf21wX= z@?-#Qfb_3#JjqKk5T*?qPiCMkbOsK|3vk$upMS}30bR{7ZP<8{e0eW_280e)CR79J z1%>Z8ixMey_o5e6~ z)x+KZM;jnjPaKQqrx+kr2g0;f2X;RPg}Di>QvpFm2UKgrosd^(rB0fRymUv?aFP26={Q zOYA<2ImG}e;e~0lXn>TsV>1$xlzR$4ZXV> zZMu188HM%t5;`rh~gNrlX?ae;%d{VFEuz59%;& z>CV#5e>F@SVgoW_il?KG+5_;fhG|O=R&B^uj}U<7B6k*2Xy58Kk{-26ki2&L&?Q<79)oF=pppUd4M$ zTp8JgzrwdpF~-R*qPRB3$p&^~%m#L2%r2pfHpa=elGesJ*}!g$*}!g$*}!g$*}!g$ z*}!g$*%PQo8{=eGlGesJ*^@|XW1MVYH^%H5^0hHewvDtl#>uw-0Zq|i+OliOH}r0d z*^~MD;Du?+o*Kf6LX#@e7$+OtjWHYCjWHYCjWHYCjWHYCjWHYCjWK%;3(eX^8slU) z)}kCQOj|a%8)NqTzDUtw+Oii61a0UrZQ0GU2y~dXY;ZTm>_yaUJ4G7fWP`ggX16dU z;uL9&lMU|1m<{g6nB6K>bBZ*^$zDO=?Z%i5?#7tCnkn^8k;XXL;BJiB;BJiB;BJiB z;BJiB8>wK3Q=~CYHnmfE@>;(vfT@Yi zkn|0P%{0-(=IBg*m^OPCSQf*yWpB5!GEfsiaMr(qC&oBf={Nvgh8W{yg1a$h4%&?| zQ?8yzo)9zE#4`~!5lb6ljFSoO#)v?r4bY~IaWYwX$Y>Lq%t5;`X6jWG3ZSXGx{8_@ zrY#fPjWHA4jWIJ&rU{-V{UC#73XO3xqtqN~s?Qvydf}-a{RZV{g1a#yplB4Afi}j; z%om`IaWX9ev@uR5xEo_8xEmvag;KLN#>t$b8UeI1PA0e;V`igNvJTHgc21?uhKVsw zW|O)JbZ96tqRAJk&8+A^4EfBZijPihjFY)S@%g8XaWdB_J~Fj2PUZ%g40*;lnH`F; z14GnOX)a4}0=ZGD+S$2JjS-;ZS`Cup5P! z;%%xsR&)Aw*L&o2SJSy;4qHUIu2E)LO-ZfRhP+n0n&jU~YFAUd`&duyN&j5!pCH%c zX{tS*)gO)}CC+x#_MXGZTnrkw5@8g{m{ku6z3R~O^X_0wq=d(4rNjs_*c!FHfh$P- zxpNx0BE_FO)0mGFVjF{o;Hba6pVJe=1z+A7^_hQ{E$aC4?(MbXl+8x=akXXl3IGy+@976la)F0NjkklX6C94jgAmo{p@68Ne00q&dKcw>$v>z~m zUunD#>E8kAe@Op|r0khfzV!w4m;WLC_u%^<(ti!w`;dMCdaM*M;WX%}wE4;13z%>b zNIzi0J)pf0>6G&WCXg-#On3yK6fohh0Diy(siFTNU8?8@OprSIAJVC;6fmJ2C#%wq z;uy=~P{l(>z=SS9rGN?R0Q?W>PohPo59tJ@59vo(sCD#0n2jJ{0&71<``Lpm!~3YfrCRtlK#6!q$W2_!AMoR?npmheLovmm+; zMTQ?yKLgW@;HMY%C>_$dJm(O(km6VNw$HpQM6Fd({+;28l!qHP2}5iq=B z>NphoQ*|}UX{s1Q@T@dpe8ng@dxf79&>TI3d7fAILTqaEe1aF$a{w)}4^8+*^%B6k z=*3LgFRC{ii9KjN8<3oUuCFx8=mwc!|7`V{$_SkUx{M4-;n#H$w~WyBOd&&37>Yqs zY$J3(Q^-j0OuW~Tl6s9@@DlFeUfN&$G@Pky_^`4WxO8=uyO(`}G$UGz8(_Fc*?!P= zbOAw60Z#OfxTS_01Vo~}n9{3^wU0*|33>}i8L5+q`joM#8t#yUz!;B1EX^H~DwNnE<`s5IIhOUT=sTFF>z1M3xKC>kW|= z0`z)A7e@=k>Nty747|v$OxgGiuOh$GE(RW zWRP%#fOvEkG)0;Oq$<`dH6o*g&PFFNVYC2rCW;s%H2M-nj1`()X+*{ejh;jiM+uFN z9AHGo3ypppXhe<{8r?X^h)fU~y*Sv2OcZ)}#o8f8q*>^uinT+H$Rwf1pez(TS-^Mz zlsrX1GXRR7Dqt!A%AO`*CIAYbE?_PIN}nNML39e6G*duJ^ebFVky!$cl?9x~(3jo< z4p*SP1soyu0uG0}w}3-goC`jiEA1TkmG)a;m2qo8%s*rS=Vze31spyQ5g(|Na0 z=hC0$5Fgfkjx>l2s)Xf>FLM5RiukZ@9MT}dU0kmAMXtCCBE{}torV&O&Nm`qI^{Y& z3xy{D;nrcOGv9^Sp>GFRk&Wh|CIo$vNUK?_0^UY7cyR57?48IilfvDHz8Zj$OLbO1 zIdZbjdXLVE9vy^Us%`Cwf=7;rjyfn*+o@6aNE3VHDfS4PI~@|zBjb+;`w$-nn>*JR znX(BY(%b_qOlr9Ri89-rF17TbU&|8qYFRc88S&TU5U7f5F|96}a55w3fZ(${(hi~l z`Xcj8tLsR#!TiSLo!4S-9d>R_L zJCUo%A1dNT)V>p<*6U0jR)gfSnUwj6codVIB&9X^Xa{#xi5p&w3_J0YszJf!pksrX zzL4yyz9gT10fTV>^r`K?2Q%Kj1iQihgk*I$v@*U9@Hti~0pfWQt_;VhP4&qlbv*i0 z=)l>Bj?{Ck%7yz%3^-MASX=>vA8%NE)=LkI&6UW3zl)d3Ns!YP*xJ;7qYD!Mo2^aD zdLr}R4I$auv~1{^ObEP?l});ooWKiN*_55a>3AV4Tk!*Oyce>0xN<_B_kk0#pTn`d zM#Y(Ufi1sH1`oYi%J-0KRI8}$PA%p4@Eb&x9kP!D%L^qECoL{6PI@Pj zt6#vIN!ID}GBwj*!|6xTNGv`PH+`HtOs}|ah^C#`5{d{v5?f#5#}kX!8&2cv$eBW4 zoQ40D?KpgdpR@u6{Q*_2cLvkNAjY`sj&^a0y^T(Ew2MpZeA0)rR42BZC21Fz*t3+^ zE-ta&l+i9Ou|v=mj&^a0btkP|Tw*U%h6CNGGm_fH#hI{!CDX;lnMl%zEoF{o(r2gW z;^ItZoehCMfiUYgrp&d7)kBo;w=0f^+}g4B5B0NF`IUAiDlR~Oa2pl zCngnWWy3e4bEvA4?_>OVIzx6Cpr)GNvK;5+J^(R(l5|cXX~bw7<9IGEA$uuU)w@x^ za_9cVc+4c=;^I6Yk_ouDINHS}fw=3Ac5#UvU|;IE>#=j$mpblxVsYznhVy6z%818? zux#z(5}U``KgEXUW7Vw3(~p#)FJtq%g8s>WfUb`+{+O&_^Z~uSDKoFz=Yy<|6po#U=J# zd@ys~ehKZK8vF5~px-?U?VcIiz;ZvBfqKr3y-b}4c!ey8Jw*P8JpacUY5t>lMhyFQY!s#l=083gO~{TH5ZZY`F%G`v}D}h`6KJhn|az zTgDW)xZtsoa_QpYcrGsP3W~wS1t|mEyQtc8adH2H04^>_8Sb7&vB@T{$0m0d6?iT# zE`vZgQzd1*JCWtU#RYkq-CyAz*U0UGaeuF)I1*J@CC6=3jQ;?Sh$<`zrHzA=usXsBM9q8{2)2 z-3o6PNICA^6kBBS-dXPsXWcw+7xzs9F9f^$92LOZ1traOv#dd@$u<+6vfRKObd zN#;3Lz(gY{E(b``k;I;(NPP@{z+Lr9)gpFiRDTPvcCF`#59dKXc&i0_?W3G6+MOI@T=%80{3HnR?$Z^G8S${e{#!?rAB_*tsL+j9IIc2@@(YN zpMj3`#VsIm*#VG7Y(6}EB9~7F?If12TW>_RK7%=OBt{$Q$ets?kHv`Gyv<*WoCib}PqzO2NITiWAwG!oS!~_S+`PVRJcZKaaHcX}7YO z?=!V|)GvjvFG~Piso-KIHFTwhElR3blq$9=siV6HTJVL0%DhjzmD5%tf5>jf@sP7{ z$nZ&kbwLcw%GsO2s9lUhDl%040{>m9*)Vk?+GDs(!X^Ms)0=Ah=uo@Rd7jm%cpAdB~5x3Z-V zK&^b(#aEjNR3?*%^@`tN&=`K$tz0&XQeq(;xm@zQqdG&$m5N<%xFI}DBiBkRQ^jLj zkH>!6Qn7kB!m@TMo-psjZgiClBwk6;(@0kGz<|dx+Lckqx1tz=pn%<(Z$(wjBE~&@ z5BOqLM*KCO6Vv%tR5gX{d^X;uP6ScJXW#f*Re*ZKJr2!_ zuM=Pwr;b9($pRerFo?!a5fE|N74cIA#EavoV7-8p;amYd@zYd_MO+@g+N^^{DdJjF z7r|}F^8DJgX>w;_+;B%t2qHstY}&AZSC-CS-%9=}CW`nn7&9N#5ifSYDHy9Eq! zmonv6Q9ayUL)G7tlqQ#p6!F^xjB(!~*dwaPyWEC6e!HYhb@`?izeB)Gw~mG0DPXSq z5ykEj)eBs1Lmt0dQd(S#;2r_Tx}Q<(UQxZ=y#WI-{(VVVQ)C?A_zwiEb5CPMe<)(> zU2a1jzfV%mc6;(X-7jF1%WcTx4+z-oavSpag95f-I>UB9WHL%pJ|CZKUB;8fBBok$ z(u(*NAD&@`wcP@^VPi&A{cBW76`Bbh8T&30vv#$Mq-hGNO5idzL??*hy(O95-kE!0R6Gi zuz)N;qmgJ8kOvrGB$f)O0~lx|julW3fEp|l&$M=>jfZYs8;lvP5HDYm1KlY|~$Y)2WZg>Ejkqlh&^Pc62igf^jP z7TfV@HPJ3$E&xhcD_}u!WxJ7BCv*$$-t6759eHLMI>}oi`$5a&&fLEmn$WwghWQe?cI+Si?_&kck$!2{zcigA=0K8p5*iEDG)SUt< z+%k&YB>*n1HgA|An`74D^B{G%`V8g8XF_FV3l1maCnFg*z_ODUxq`?-hsGN+ehN)`5H7Ep%uy{;s~nWUZ@gzU4y4Mx(e z8TNf}s(WEv)z?hygqd;dAyl=dSNbt7c=!SRq`IAnML<5pBhB5Bqv5t4@N zHLHZAA$$5tPI{tFdfPdW=a5bBp3R(zCGE!>={<4}GbEB``i>{JddOM??0^ zCu$2=UDQ(K%+CD@=&nO?l^I@`+Pc ztuwM`(U!)DJ%1>aZQuoA%ak&^fr{g?%P@$u8~Al0g)qLPCxRZ5SkVgdQe<6l*y<8# zrWjQ+yMe~g3+xo5N@h232({QL8nS0M>_!R<*_{LE4%bxdk9-P2jh;n)T#L+<;`7-k zF2!<{>#9E^w++xAZ;1jz0F8!Q6yUh8pnh%_#r8yG(&={hW_-?dP~-Mc+|@8n{fEvN z11+=Ft7rgdC^^Qb2OI7(p{viqfasQ8vk~=-U4%PYR_`|+o8Of*Kl9kJ1QcZ3o&)V9 z)|`w!Y&!rtk~kiY=Giu0QSsQdP>^log_Me!Li4K0#*P!3*GWF+2+ixE4paJ-kmtCE zvFSIcZOCRFD%pGN&Te%Wf8Sya+UD~%Wd9r@&d)MfGP2ZzNUtT`QoBn%2D>4bF9o%? zsjopBE_=TAPIV(964-7l&PnaPUgzzh*nI*jip#LVSNo9K1+j?xHZs;ep&kLqyGNtM z+GhlGbBoOLoT5X=0QUyeu6DoTH8aG$nkn9Xr78J~MYnbwddLLk} zdnxPowTzhshI1~?Sk4g*-R1hoMMXnbi7MH3D^9NJdMqk!cBT8M)is1(wY%!5lFt1| z&ZX2((Q96AS9L`Lx`t7IqwB>us;=*$`glu!rvb7B6+*Hn+gbXgt3;seDiJ8VK8dTX zqN_xp?0OeEKGjtsPce6ast&FZ4P&d_8B2ad1fvDA0B2adf z2$WrQ1WKnG&BzT_^is|{x#8+v5bh8%n^YsT81A>YoN{9nZ^*dtK0q~cW7Q)Ni&NJ5 z3}xjeslR{@*$RtsheUA5@Bqdg7+TKr=&;;u)d{SST~Cn#zDS0{4c}p?b+Kv^iE)&e zU6Npn4Cf6NbE0Y$iRCz^cVMia>Ps2U*X)cnYNH5TNP+L+z@OA5BTphZ@Ropzd>`#)qxbybOgCb;GT#W&b}WiPm>)^niT#NDCeo4E zk*wn=(q5TIl1|00rk*jRv#}dVk0b3xpv)gtL|G`a`5TtWFueImO!vy1LfVdF~5X#Bo-#Wm2^Dz4V$!-bSic+j`?FrXJcXNSw=b^JBjr1 zr0Zf!nRf;0`q<^T1o9`4?iQ5do}O zY4o1In80yTj6j*+LJ)CMG?B%5?+{PKpsI^VbvfbyAE#ncq$@z)8_`E`KAz5GO^W z_xuim;ZBO)>G_?j(YPijb$}^15uEL$7=bc>Gr?ZxFhrot-?ENf5I$@*=v|vgSEjbG z$lcO6(Nt$o+o0%d;BUgnAGS4oZsnOPwMC5O4ZU-I+|6A>u? z;xl=!goy~0anK^k(??e-PW|bCVwL}OJD48ZX*&tzJfqF5Syq~Z&92ouas5Yt~J(UT29|-sLCO+Kp1lIy{QlIU$=3b6#N`H>q1e$44R~ zI`2Yt2`fsY_u5MpADxC{) z5T}-qeI1UK_u;^woO+la+7rm-`vd1#!o^|?pO&0535KPf{WMN#$d00Jbu@af9cuFV z-t!~Ks8MCs&XMq_jH~H|I$X*t5b9?(8`iKIQ(QHVtuuOk(*V)=-y#D-G#vpodwPM< z!cxnuI2k+0SjPI4S#w7iPOp_@tYx8P)|p`RehYIx^=td(zPNiqr`moM%Iot2CKBLs z-l3-UT?XrgU)!8qG>n5x@5#6z5OCwMQl4i^d0r3Zfe7+Ul04-s=UMxN z^Q`1KN%GvoIo@OTm8CrWihkW53+8!D@?0i)RQ}oYO`3A4|8HXmbu*%PlbQbuEE zzs<)4+kA|aFdKOW$u6+R*qryP>Bis|o}H04=gRLu3-qBE&VUx(3nN9#smLfb9VvRQ z1suY+9(9DS=?r7={cLR)(X+Rt=c$sOE~4jQUr!g&^HxbuS6@%>)2SzJ-v=G&R@8;t zOX|ABMaN%|X=oRWWr~C-lC;YqGprwY`J=%&{BfjQ3N+l`>$LazY~{<=mLAv`6IYtr z{@0S$mo1))KFBC7eA(hCTmjf$TKI~^Q+g5bfWtB5mBv3Mewe5HRg0JD+rT4U>4}>F zioP5bS6^8Vvr@kTuXX~6-+~wpqLHa1{|qz*=m^E!CibcKhr*N6L^XAw)c7f>G0uJOLCmtn+SeUB z;7XPwyZC**MY6P_iv1B>?Gg(K#-%{I(U*#fyMX0PgixlOiJjI~6e?$8FA|NRC!+c> zq{`sjWqr)lQ^ETgQjhc#MxG1KpTHUO8Hk*(?EAz123S53;lS#^d%CZ5jT#NTx~~_2 z%jb%E(CUKv>Ar@z?rRW@OqIT#3gq?m=vUEP_I0TvRbT05bT_W3Q5-49S}bG?ero%T zr9L@U`eY4M>0VeSy|5j)iQ*h_mq1wSHKd-e=t`T;kx=~tyZe3f%Wj7Af~elu)$i{2 zO%B5EmsJ1C zn(n`^c}IHMd;^WFlSbZ-ETge=i}M?=FV=zG`x0I|H=6@`8(4-1x&4yvIIBF6^(D{h zt>#9+VcT$MMXegi9C<6yML;8e0OE%v9tZIXh!G6>wHKMQmB>8B9D5itzX9F>W+rpw z0iehv5TAmW3}Rd!4~x<`Fi%Czj1gbop(Z_JcS0Zy4^)pt2wyw@(5OYCvBhd_E9EnjN&IHj&`H{5n-v%^t zJ&1iE5VwvBN1~R?A)tCHQ5KrwDXS+zWur+@*?JI-loe%H1BtS|Aow@*uV{HY>L*X6 z3Fb{~To?^Dr(!hu2_tL3$$>Kx7oIT#MAMVV!;9uLWZcG zYA@*;y~bl{J+RQ7i&|z-b7R8EXt|1;isN#kOex}Wl{d>>xLU68No&`wHB>@Y2q&#= zU+UAwgqN863#E9%bnY({?-7$Yz526!D%6U;luv8M1cw=3SE?6Ina=QfM}}VnGQ8ns zI0AjAZcu7{DZ>qtVKPg&A&}ul$;B05p`20VU9aqzd9Hbx-pZh6fYK? z!PRY-?#+qVq@^ceF6_~4q9%=LH#Z>jw`wEuP9H@@-*V+>vdohZp^`MpQu0Y|@~R~W zuxScC3E>qjts0L=TYs{f_6W6os2(e6`;gjZh_;XTA#Vnh{f3|SW`2mn3y@O{t zxkE(eoI{aqFo1CIu)!^!PqMkvf^C#N4)>K_qVjsmtC`238@J;DYFvO6W7_4+e!k)Z zO_y+fM+p~52@^g>nmNg|Dp1FXKi8laYHG|o4-XZylWEOktXMM%;(OpEZ&22}r@%>G z2!b{-3E240+l2m0z{Y*PF?PzR4tw;VAjMOx29>7ui1LTS`*J3qnH}Enf4BG}`BZvi;fjH6^ zIpS_0{>|rYVl!S%wgaf`y!QS!31CL2 zAZ|5>Ee2i<ZO;!<6LuOo4?E@6{jLK9Q?@;3{r`Mf$A$7z^{ z8%t0Q=Lp`T&KL(vV3{+NB#imIh29IXO|0H_p4MSo!MYaOM{Wo4Fp1kh`~t+H^Fa8W z`F;iZ9P%UY2lI2JN@xBr=#tTLp6ZH3=}e#Jcczd1&h)Y0nI-IX=A0S2FAeF;KcNJh zwY@-XW(n*}pXYa`kNwW{vEP{`>~-c!zl0{H@a=myRF}HW>(6mL@Pzz(rg3xvTwX** z>pUF!OV+EUZ{bqouP|jPV*~M5nB4jZ=IH$87MZR5+{RySjoJDMCfNMt+RfHi!Q(I2 zX10!o2L2L%RK|U{W7@_8O*m@TnLJK7U1tpF=HI@RxM2ih!j`?kyBB>*j56)rC z%e1F@S-{OE)N?7tw5NKR=c)cfyiA0|N1{yoNQlQxNPHy90v?46T@@Wut zoDLreXE*Q4hWJQ0o{xm}1WOYi3F{t`2l+^N(GJB&!s04!IK2}Zw2wr%!$%_A;Uf|5 z&qB11gr>ERgr>ERgr>zuBK$w_kqCGANQ8&#CeTMBJWQ8FABphcq_vMkcsS{Z_(+6D zkdBLwM0h0Wl=w)5k06~DABk`i>Ad(zgh!FC^L-@39X=A_fR98t;3E+Z`bdQT8y|^q zhmS-!;3E-U%u;Rfkq8HTB*Oo5ABk{>k3=}&BN0ATG~<&aN3`~l2$y^$!W}*m;Ri*K zJ`&-FNIK#p5f1oBgdaHp{FwMigabYj;m0VS6(5Okz(*n+@R0}yd?dmFABk|lMZ~+iEz+IA{_LQ2+tI;sp2CM4*E!h zgFX`BgM1{y2l+^Z5Au-+ALJtu{(Bz@cBD8(NH6odc}Aeu!JJ0hWc)Wi5}vsDNRa;b zeI&v`ABk|lM zJ`&;MrJSAOBN1LM{tntlBD_L?_K^smAVB*_gijQpeI&vw1!y0M@G8;vg7L5WNQ47E z65*haMEIZjNU&26@{tG!d?dmFABph)rH_O+O8*-liEzM2BCLHR#4ER=!$-opAG44O z@sSV*-3sxMuuaU0#6h=0d?e&6yabQ05FZH%9$zVr5f&XID#bCvIup&W6vqgQjuDmO z7-7*dqEZ|qY}x@z@c768n!szv2=mgPf)>XJ^RhQVYR3rkayme0#|U%l7ZE;zX#-{M z;Yyu$j4EZ zsed18N;dTbC7XJJl1)89$)=v5WK&O2vZ*I1+0+x1Z0ZS0HuVH0n|gwhO+7)$rkd>Xj4f7{*=~aFL#ScQD!>0aD zAPEj{J+>dDwyC#X{06kx)LZ+Hg(fjjwq7Dv+tgd0O}zw%x1I`Dv9u~256R(>;Q@@N zATKuc>w$fndeSAE`V9d8u1!6!y@PG)>!2;Z35QBXYTb>We{Ej{+PA4EKiz;zyaYm< zwhKiT6l$A#y6=n7pGrbPc|tU&2-$B_h^HYH_cbvADY%8}lnMi-S*dwTF%@qBxok@`yFG0kKU5YjCnmL1^EE2m9OaC?VS$I6Q zll;Y`VN*~3QqtL2o_SATlk$nylZ={^NY=&vgpUt3?G&j`tXbD?)SODXTVmbnHAc-D zq#I(_QXLtbPbyU+DNr?-EoXm<{ zD&#W}^vW4`(}f+y|+>1N$jx(}pv9DH#fNKa;6wEIAM3Tf>=ke)_byAPzN zlh*D7=^0e1-3QX1`+&s3Pmdad1la80cnH0nGdzItV^l}t;HQ@eN%w*DDk14Ukhzjm zgQ%0)wjJ_xAIR)(V@`1&$awAp5(htX$C*f|q}+q}c~^wE4`e@4+_O!)54dwb0R0c# z2P6)@yWlCLN*sK5$(JBK_W}2ev+=P;+y~sVZovl-?LOdc;I*&a2iy%*tlbCP4fOoh z?gQ?I<3Nl1fV*K2vWokFM{4&0cf%v(Yxe;+=sw_X*oze3eIRFwpJzUmi>m{ukGK!O zd|SS(i~B$>=so~rZ5j@1_kmo{eIVCGu|3*-Aa{`a0Iaj=YZ0e@aUXyg^zYCBaUaMX z2i!Iea!gXYqJnKd$KcTJ18&>bptbve+s0dob{}xtc=OQi z18y7d8QOioZQ~6>yAQZ+yd`M&0k@5pzIGpQ+jxn?eZWQOA)9p&6EJqCwhpBG0H+oq z`!h61+y`JB_$t!1`#^q|`UMQa#C;%to2tR}qTL7bcdAQZz@^;>@l_0F2tI|eIWmq zdKlWY`#?VEK9CQ(59EXH1No1o3EF)i|3~#K6lnK>{1@sa0PQ}IKgfNcHt0T38x;-z zbN2xlME)8*s9geTJ4-wNRhNL;9;%3Tdpi248vy=Qmw?*AY8kTSo!a5*MG)c=P}?NE zt6c(W$0$BeJePplv1$**;*=GafZ9pwW6&5WI3DsB95OtB@eGEGxCFq^GK!lkB0=DI z$e}ohNQOg5y9CrOR((WbASK3@B-kSD5>R`hnkEu+a7^>La-1)vT>@Z?*)9U>DR4Co z{ON+k8$b@8OTe4Z8?7sJFT;~YTmlLKmw-aRC7=*+2`B_y0tx|_fI`3}pb&5gD0nUb z)}%5lBn;e+>Y&VFr?E`B1QY@;0fm4|Kq24~PzbmL6ap>*g@8*yA>a~F@LU3{Mm&oP zN5xSV%544}%cM&{A>a~F2)G0k0xkiCfJ;Cj;1W;>xC9geE&&D4CBWK<>1JW>CX^*E z0fmJ>$MT4{1QY@;0fm4|Kq24~PzbmL6ap>*g@8*yA>a~F2)G0k0xkiCfJ;Cj;1W;> zxC9geE&+vrOF$vu5>N=Z1QgmoL{qd&Kq2T7P&k>dM4n4P;nc4wrCkCFL6?9+&?TS{ zbO|T~T>=V0mw-ahC7=*=2`Fr=%HxvNE&+w0OF-fLdZcKVfWigcL3=I%h0ToS=D7qE zf-V7tpi4mEVj7TpE&+w0OF$v$5>N=b1QdcU0fnGTKq2T7PzbsN6oM`Rg`i77A?OlN z2)YCmf-V7tpi4kuCpR|rTmlL=5qK^Eg_{YqOF-e4rR)N62`KDZOIo`G6n0DBXqSLO z&?TU7+Z7P=TmlMv?qMF!C4l2WW=n{J&tWdF$2|SQL>&B&eJ0P9FyUnUtr{ zr$AToPBheKdM*L1mIxsZKGUQOHb|I=gFl%}-cQ&Xk6FoUePaOgjItS$jyU*C6HRQ6 z&ZHmumSJBDmc+p?-2Nrhi??fPA@n0(s)hn2+Zp>Ihhq zi%US>i-RvN0Suvz{w6 zUt9w617(`vX=;)(BHDB_KT1ucruzI*s)(n$xCG>bE&=)3O5rxGT>|p+1!$Lme2W0> z5|9tN1muG*0r@qeS-S+}Pf>@V80`{}54r^8H%cYz@JwXqglslUTmtf&)K#G4y^s-2 zzEGXXiqa(@f2rc5Q@aG@uTXscX_tWfb&8Kn?Gli`K_)|JGF<}lJJd)hh*JyJgK(_8 z1qc4*)YBzkD7k!1;=Dkw>s!^oPXH&Es{TU)IMHf0js@Na_5ADqJx?LuzttqG|IY&0sxSvoh-m}g zM?(Luo+@&Zr+26(hAoGve$!LUPI;gjE!&IUR<#yqCc_6{Rs&gBMc4VAQERa?eurEG zW+NH1e6J%qOGhAzJ^ls_#6_oG5i{*O8)4fGp4xsA-g|YAzG70zYRC?5g-zKjCMRZ> z5W>vsRmt{SpoZfU$oHzrm;Z`cm@>n5>}QhN4QS|x(7FLShrNtbQU~I2IU{e0gqqXq zrzjckXZT!&tgF@@Z>V=oeit|jnftLPVF#woIX*OLcOkv$^Vpj{-O-yq$L~!a`@K02 zs^zcG%g}u~79ubhU=Pz5Rxval9nNB(L=xvsDrD_Ku_JgAeIAM($uuc)1W%x!f+9z7 zZ1~tO@+7}V8Eu_$PGq!ISf8^=9Bn?&A8kJNN1KoR(RQw<@rWFhaX^RBx4IohpT6K- z(nw58`@U+r*#GwDNPh_Jl7aaPQ_A(RU#^e+a((QVdyU@`vFhWQ)pvCx&XF@H#4)u) z&frRv)P(L-+gUw5rgq4fx)VAEw^EMN_VR9{YnkNxT&0%iP@p|uGLv7T+HJ?0iDl%eJGIJA7aV`%vt ze`xvGKhFa^^;-Wf=$G^Skoj9*zt5w7pYG7_bA0_i_VthV^&fFAbaUvI>wB3VzHq0Q zZuDU$?-oZZFQey6ylu9dW5DOFKy6=EIw9?HLKZ-6gIt&Ga$Rl)mMiyU2sSN8zS8Yd zPCMCh+7pNo0=nmqSVF4_AixY`#>)L}f@H%}k?Z?Rlb&^rI28?ALd``_#P8jYa2j>*7Nv+oP(ytQb(Uh9 zfX9jQLv@{|9^BVm%vI3vZ}s&OuQN)0Ed%^8^F=E3`uRY4Pm5TpJ zihluWkKVxx;x~$E*a0UbHg-K1Gy6;GF=WMU5;gy(l=UUa8k&m=SEFh#Ktu-d8)`xi z;0=wPa6Amj<5}=c2UXY%e*Xt#^`?u zs(CAFV6z7ItHy1>*FahShXV;#XRGlUKOus&&K?BS_HI2f2u|n4a-1T4J5B()Ue=54WAMmn zH`H=T?F=L>VifdYYw*N*tA{^P0 zx%fO3JCbQqq|99W6ci~BOdtD2p6?eacaSyEEf>-bbq{pQ9mMDPGYB91GYB91kKk>d z#v_(P*>eqsLGy5b=CT1iJ#(3Ao+2}sGte%Xxfp)gE0w-;dDt)4Pxs69v0v^zeoJ%& zDj8cm!!ovFM!YxZLF;&l4wUow5XROp6t1?jl6q_nl(DrBn)L7)D8uIiU_Al`Nlt5? zH)DAOD(3Q33{mewyUbX8o5DC3_Dsr^tWm)1zd=+-i%d>)6CPj?I{ zpW_cHAN%Kbl&4dJCDjMrHAPzZE?YQ7W*qPFjZ7vSbcdq!n5i-+_zm-T zH&-Uf1&}r3)G}>14(f3&;ddZh$h;1Goa*00r6x%cPsobze0Z^l;=NLtsWT3Gqki%Y zX#BVOwg|=io8iAu%gEd}7_}*NEm?lol0LX=$q9BXvEQ|WJnec`=iN)aDS(VhqxtnL z`r^ta46Zt4RNLVx==H;u?1u@^FiB?3SK`DNCj!cl}7nnzI-mbJ7bJ0T!D zLCYRfhelh&1z4=B);e4yWukA5u;ikcb2rYORcBcoyjrSGq>OndQHKLptRIp1o3iHI zgwE@Y0NnXwMwp1*6)GjTK)zEnR;$SB$scc5vRz!>#HHZ1S;Q4VrJrE zD;M;Ss00v||J4(04n4tac!DAJsWFp&O_ z@zQlZ67hYi+d&-DcU?Ko8X7MKD~U{v*MR5;V&E+xdgUO+%8jQClcrFH z!mS_%_{jrPNJr&%vU1-?YJXO)H!{m5G{KbGoy@$f-DVJd1|jty)owvU0v9oU3s>X7 zU#Gt;dLChfi5u!E^|vSb_Ynk`=oO@H^0%lPdZz<&z#FNoSGj zhF2%qebQO1q=vHlq|>6Lin9Bp)2gJ7viqd7LQ$D#iCaFc5&0|ap*Y4EtGS8?MD`L} z-16Defb{N@&QP@zAS!hmrXE6z^zM_+;R5s?k?>bL5g*j`?vu_4sh!?^5?dNbENDY) zam(l5LCyPEmUFb?rVv{5grMf;pytV*X4>L9vsDX<@oaI+TfU?+2~zH?QAwo8?vu`X zwU5;_#1^-FStn*$jH{r@xm@zg?vu`yik+@^pLDL3R_fg+o$XRFz5ArIQ}L8}wz%O{ zGL&eG8$OMs=M7fP*yI(q^B!0U#wM?9W@?fRWe~K~DL7!i!7K4E!Pw-LlgXC!eSSKY zEbe1EO>!%zkX@6-HhDd5s6KMKfqn5lg*qe3*yPw4kHD^AZ1Tv-0-PvglSfVw5Rt1s za;kuM#W*ThFCb;4ufU@!a+-RLRiK)qP=r)bVMAHa!d&1pvB=g8x+Wi)Z0!S4F$21$ zT2h&cF`%ajZC5ZLc4WE$2Q|j7bu$D+0QzGGIsw>Ub2@gdnWkBr6Yynv#&4AdE zIo1;VlRCT)LMjI1-Iqa&@osb(N0b=vMpyj_)z=#^MlVd_ZpRH6qZcjagvr~0F?Nh1 z#Flu2V5_7)gc^duMr?rqy#Zrvp#Z%BV{DNCy#Zrvu>idRW2{Ah-heT-M1bCaG1e+T zZ@?H^DxeM<1r9V~#|qFJFv8r9HP9O{#*P!9H(-n%FF>DRff>0%FHj2`w8i#!eDiHeigc7Fsr7jI9w`Heigk39UC^jI|5U8!*P!3XlyL zW9x)&!M%dLThmhYxoX43C8xLQ3mH%Z{f(+W3$UYe@jb2TO94)_r2z1i0PM0l-KhFn z=y=80qX7OQAQiofQhybYjsB3}ZvyhsbMPgu>Kg%d6-Q2MHa z^kHUk1k8-ip%lLULD^g*-Oh$qn9DG@GPd)~56~^LkD~Kp9qt&ikD~LMkThy`-sY&4 zeH5J!D2p!TQ>M}$2Y#jfGFbNGIC!q1p=UvJA4TUUa%)R|hEhKPFK1LUet0~ixQUC{ zI#)kt;xa0i_~F$r_6O~7yNv4ngLsDvFKsodUn19b7(cxFW!A(o#MZg`sS!x1w2#Cw zHW`O19>DlBl-EQOH>*2=ql_P(xJ76q%J|`lUFru&u%q-MNZh9Qv~{A4AD*~fKsd_y z;fXs1R7A@tc9(!kXy;9>(&ouaV^|r9yA|DqLJ#4P+=s)P`1v=@XF*ppet6r!4eSz~m%f#Lx7Z zRTQt{V-Lwo{p71l$zIC2Okv57lu}AH_H%FdWw?uoZdIwmzRX_Au)cpQ$qZ)&crH-^ zy7lm&;U584S=0xP@0^~0wdUG2=o-vafk84 zlha72oJYx@PCDx_et2>QRpznX59pb!L!BW8z{ydU@bP9}fn)4O9IAK#qXPfL064is zNE!eqR|!c2;MA3zksvVVwhtl5A)DI$2y=!RKRmUEMPMfMBDy1YZ#t%<#;1FuDi;QBO-VjC#41m*&AD%%76^PfQGI7-lnxc#! zo=K?#$Y4}3et5=J&w{oA`Wu;ofDk~VktqsrqOTxhri)^GA~GY)boVA>>Fba+(?k6n zNg?WY89zKTTXD-x&`@%WPY*US%Y-hM_~Gd_zk$5N_~B`70PN5JINcUT|Jx4Zho{?m zgLcA}TN{P1)euc)}g_~Gd`UPvj2@x#+?ylS!zeWSfV_G z?rn+#!icix-8TX9a@d%ezM{BZX^0TmUDAMQS+-ho&o`ZhAUPpCfvlx9ru>})k#L>5qF zr7u#&A!MYRsCBWT>rbUkpP$&JB?-33NWZ~iPE^}OVkeHZ7EaAQzLb$>Oz`X)^{5E^ zm;&$Nz@OAbKV3M&tDeOH#dJnezAo3D&NB{Ug6DdC$`t1=9C8h$ZHFxk0hOP7!y1L^B{cJz@CI)O=7xN<`mL4wh#n=Drv9G>7*mFIaF>2X|K##q`h{|Che6uhcwEh z0dQ{aizpM$13Y1MfZZ(x{`E* z!x%S>@N>lMp4uiGi8>+~d;JK6e zT4k#u?^C%`kEE0;uA-{-B4!sE6Fhesfo&HV6Fhf1fnygL6Fhe&LBuZZrna*P;&!o) zZT${G$}Tb{c3*mZ~rp1YtOv{6?4 z9LL<|?-G<3qs($4v%tBMF~M^e5!ga)4kukw@HxZoe6d4md zcQe6Wrw%c}bGO{dE(q5lCU|bwW27sKTUg|7>6>VgF~M`UQn3*$PUg_K?H!2OvEmO| z=RIFCPh7uEb3Djw2?oF%=1FGb=@%vpfE#@#&y_G?06gAj@-zt(2EYr+H9>3Yu3n`k8UVYV0dSNt z!ClV)ILesdE>?tbC3u>eq>PA>W^`6}l)93d>fvsB0%jahE=jr*y;dg*aJNN3BziW%GMQGyqo=YbP7siY;x*84*NEm+lrh2GQ`8z1lZ`SaxO zv!jd&?p~+($aJEN3GUt?lOZ&j2EgtPbpaHFsHM_=1;^xXao|r*y#?;M^Csb% zdOpZ$kYMcgY5xsFqtYIWx>fgLF+)v0-@Cll2e-o0_$85lxKUtLVgd4X{Sf3z5QlMX ziht-)L!D(L`Et$#(OhAKDBbNp@ijoL*a<61t>OVNyT3r)E2vvdE$Qpg0(~XHRXtY% zUcZn9bX!*k$@y27l)TO2*CV~eT4;1Tn?jS$h7cNr%GM!WmozC*QeSX;oQ*?Ca9YnT zfOktt(guo18zM%CO1kyx3w^`Sgl1{#b~e0$`L6|G^tu79F`r@?R_{NOe$Zmw`do#k zn-5A4_I-r>JFMRC@&68s8Fl&&N$+#$;WAgowL&qWl|Va046R?H5>604ZBLDZDZ$C$Kw;7~E; za;>otnlUD#|~)+l0@8iy;wTce2n{Tf9yutpK< zSfhvq)+l1<1=c8{fi((zLoKaQ;1g=c8U;R~N)_de6kkoHj79;2K5jpf!qUV2vUcSfhwd2x@K)Y7VYZ#12}c zhz8au@b$H{MiE=DE@3tG8bvg)MuB}{c-_bvMJ%{R5eu$S#DZ%Sv7Ny+it<%5invBm zej3SY)r@1+tfz3HC2qvxWP9Q<9M>g=4ZucyiA5NirzCK@G0sT5J;*T5Oni!qZbRb1 zez5mQ{s59j^1I-x)av9Wa1zPU;3ShbpjN5m6_Bh+egaN9 zc|Yh(at7*|O%4L>Ca;6GTr!W;+GGZFKG_W#3dvWIw^K3%{vpYF&~?c)^cRyg$lE!2 z5srr@n;~DH#1554m*hK;>6+XJ&SA-4Lb6+OJC5CxFF>+KauxVJlatV{hU60H?3H{G zrT0$8hTuk*ydRQ%lW&33FF6x>`X}FmWMgs<@(xIj$8lhCFeC>hj{`k8Y2i2|*#eoN z$+6%MOAd#I!;_z*l;Oz`^o&TZfy~I{Wbltj7Qt^yo`QOgN)Chm(aDQZha;2cfIlYr zEcj!Sr-3sr*$14XlD`9IeDXQuJvuoL+9o9bg5$*G;Ye*xZh+=V$v>g=$;s}>H8qK+ zk})kg61k=){}=SnNZx_GGm}36Ju8{Radz^jIL=9a0LgiV^%b&JJ;X0ADQr)AwYmuR zyXe*`jErj)cL+D4kMOa4ow^mEF3QKhxlK~ej&d&|^Lk0yS@R{qcAZDnEQLbz2AxUO zJj}EkbuLxIon_4(I-9C_iD^4^KC|W{rro3-U}0wZ=&6QzvwEG?uxhw#ta*!i8|X8u z#$rWwDc++I3MRw_@r>XJ0jY`^QHFTM*qeNphoQ^l2nriw8H&q@=TDf>nBX5E?60QOrY?k14Quz!YtkRFC-e>c!& zWJt<%KLxH}qnSd6q^$H)Y|PP^LWZ0g?zS%4Y$Nv?yWl1DrGMIP_S0~t7MS0)e!)lW zFEQNBD=ir>(W7wTi3m6jJCl`R^86KU?Ji8>NDf)d@bhm&p(VsKVtpdhJ+0e19i zrd%b!i5kp%wSb6`>&AY%rtH@^19`5go3`^Tx~af5^?37skeP>Zn27@9Y+_A)4Cn&a z)Z>%Mmh^RgI@Z*WWjfc?<5S3%EB{JAT^VJYeC8gXiH)YN1MNkM;#-CnDeBiKS}!(N zU-%9rxY%5MQ8!Niy~Sqh7)2C$UVvU~ww4Rfi_O*w z0eZ37IzfOeHd`x&mc?dkmC&--jAcYNQx==8)k4c+v$aNOS!}l2gw~7AR=WVb*lev8 zAdAh`I-y(e&c@!YZApBthGCW@i_M8Ikm7r7nup2b-^lsPY2* z;hpJ+P|AD^bQ{3t8U>r1??tSihiovG?C|c3!>T_GF7*Y3RGdI$sy!-B9*BN4yKpc> zdoZjZ`#2I=oI!Cqdo6(T;y$91J%sce&ieajk0gEI{m`#dXs??MtcV0M&eXZ|?)eV9 zGwldxXC@*XRhf!#{?-ugdL4c_yl0|)5$2{myKrB7NPmMA;GO#^peEsc!VNp}_?1EU z6`?b$g4IF$hT-3C#20b6UtV|b3x&TAJkk(^Ukf`JB6?xVcfJI^ldq?p95pZ#{58e} zyv@80PX0#7u?e4%NJdKJN{^7pl}0gF9E!&>%Z}e08PlEWsX&*FLdG?=vYBKsx(gZO4;^I?el)y;H@)o1 zut|AGXab>5>avQCulW4Q72_TO|146#-{=+I&Eb{d{~|z%l{b$)0iKEA@PTxn!TrGm zhh9DiHZiReXgd|Ik?c}fk1JgN-zbQQQV^$z&*(k942P$LtKlDKdLBGGe&}hW#>7Rk z+Y9gryBM}BN-34K;U^J_D@rK^Q;6MNm_hfWQky z_Bw`gSNI4*ne-=5hE4J(F`HH=b#BEZ)(*#;Y+i!E_#6H2xOo)(<^w`v*6ID-0rLuuw3e7OEcu3H=iaWHuj7hc)qQ#-*vi!9II3_? z9g5%y1hPMmZlDCOiA(XwA4dReY2giH5x~?-jOYcVGF4geJi;1x9b`X2iYHSzMV!h&iD7Cqk~WdgzVc#u_7jgk;nbk=5?Rn0TGa-nOXX|Up)a;Ny89PM=3cmwf%Hr~ z>iD2?LpYof1B?{b7{L*N0>l(7xfvyt8X-)IHC4uo)JXO1y^{Au6>RCGx81kaR%1)NiwHpQmj5BKTNIDGV~eRj?`D2q4aS`T*a9} z2VK^{f#c3dW8ffREqMuQ>BmAcDGt;_Pe%<&KOutP;Ljt#^kd@5Mtg{Q%AJcw(C^aJ zqTeCS=?|rrOhhSH{aGqWiv60*C?H_D%Z$R%!IJrH(EOEnq)w*hkXSIX5_P2NB?%^2 z$|((hbi(x4C31`6reKp|ab zppY&zP)NrH3YD>eLS<~AP#GI2RK^Ahm1PDB8E^5wDqj4r@)rNAJOhQQE3QG0sEhwq zo`FJ@Gf=2Xh3xdr;(w-m@jv4&{#V6||5e`Nf0e)ZpYay|tGvbkDu406YPn~iP_-hI zG|J+CRbuf!v(3f-jJNn-FaB5gi~m*r;(ygf zfAK#X8z^KG1`5w1x{sg}spraV7&LHk1t;J96yhQmSNe&;Lg4}MVuV07EUxftjUpFU z`W-~E_|t4ag2Cd-1N7(OO22s&H%7VD;Z)4}@X8+Ke1nCYZ?KT_4Hj~~!9vbASjZ&| z7ILSB&oPS2bJtW5vX>~XlP|M_{Hu6L&0Q}{I{!3=&D;&bzz$&!QgWj({qr{>fZTdv z>he1w*}0DkQ_SCo6{p-y!bGyzmcuSHD2##mJ&^m{M)7IO-;QF--7L%ySzpU-syGXQ z4$uD*uzKzj;xi`yRmO9RFcb1kjOSKiCdv9*?voPqwEQXt{VDO8p5Fyye(pA5X63o$ zo%^%|yG+ph53aH`isI`8Z`AX-}lJZ@{I#?2c^UcgHd?4BRSu8B7Ikzd(JHHGa6zul1Ky#BH6NPo|Er2j>CLW9eB{V(PR8R$5< zQUA*Pl8~${=j9Ix&xVpN=jE3Qqsw{uLxs`hy!>Ip=yG0unJ~JXmtQW7F6ZSB7e<%! z@+*YV<-Gh6!sv2dex)$FoR>dR7+ucGA0><~=jGogj4tQpj}}Ik^YZT(Mwj#Q#|R_K zdHG|7mgT(saYD;-UjBHYWjQZ@g3z*@mtQ5cEa&A{3$4p}`4ffF<-Gh!!pL%7evQz} zv9!a|ZBAD`$ZtZ#MxrXVk*JDoB&uQ?iK=I*TefU9AENXO{8<}`xu9tyQKidPg-Z~R zd|Mab%xg?Wn!_WYAvO}V_k9?o+DOzs_65*lBT*aMNYp+-soF@?`Zf}^-@G3lx%7kh zulX+iYWWAj>2MnR*KG<%qk)NyMBOKZRvU@BTf&L(P#cLl-$tU&w~?sxZ6xYq8wvKK zo{dD^o#77=UuG(TEX>B=Qe0BO(NE6>-9Q_Oy2~pl7mI`QL8vu>P$Q6L1jsHvmuCMU zN}q8`LK&rdMd@QyYD0(f9j8PO-2O%D^E2xM;diZ&pWtf5RJRrk&s*;jnwEMS8;ME? zBr)u3%TjFb=DURGaHDY5aS66MdsBz$J=^I_V*=QLB7Hn}#M(%3Kls94*FjSCEs&E6 z2TVs_n&p1*g?VZt!Ea#-^UsG$Hp~6s3%VbCmixgM4q@bVS?&j4SVkH)5|kf7I?8fC z_`)$P%z@P_jt>gDAAFYk!52=X%8+XA2VXdq^zdr#2VXdY^oZ<@NPppjOwE`q?b{3I zGWin%*$=+3?*Z`0rMvN8vlM@|{DXj27qTCG;UXcqAAI35A!!a$KZPG(t2s#h0k41- zbC7z^9Hjoh-4Rk&%t7i8Vp`N3q<$W0H3zBhCavZm^*yB39Hf3egH&^ndfyzRe#Za8 zBbN@5hMNBPtK}aAYateMkov=gq&Z0aaYE7@q`{bjG~6&B`ZNb=xK(f#Su<|%%|RMI zGaf3~TK13+QuQPl8Wfj4j7Wm)MZ=KTLrGVl`zbED0Sbc_1;v9ovJcuXC?0kgBte=t z4jf+WZo^=fT{#>#&F2UbWLr8w_mWO$UtnPJIdL{Sl{)e{asTQ$fIy4#IdNU}JkpD) zU(BA&dzUfFDEln+<-6g5*<(n{cf)PjG<8-`e@Kw}4|*K20XO8*Oi6)Rp8>)&@&;q! zG8UqpjD^dwpj*YlrBy6kS`!v72g27_xbW-$Hf!O+uknn9%g9>hQ!QNBommSP25c={ z>X8m>;W7xcv2fuh^h*beg^Q3C?P}q|PwAJY+kFd{cC~QfcZz*kxEzo4yd4V{=4UGw zE=};tFnnv_aw;-rEnEyO7A~Z%h0AcHvkwcGORHHvYT@!Z(AL7`JD{zF3;RQB;lggv zTDY*!vlcGw<*bDZdoyd{!d?p&E}uYZb7`ib!0wa9xihEZV&TF`6b2rsSPK^#C^!q3 z!|PCzL!b-`mkpo;YvIydLfW@);W7wn&cbCp7-!)^##y*VXcY^WRam5(c&KHlYb{*XfJRNhf6a&SSIa*L zx=>xLh0C>~@^Pws)~eL93I*1}V6kxdchEs)`|t5T;KJ{dscQEv zT-tpLmv-O6rQNr1Y4Kcw{U5nfL3iST-tpL zm-cU9zF;j}+IIB?d^=kSh%#Sh07q!w9_^1YT+^&3@lvaouBnVW=pVeVKo;aAHN7;;j+dG`K&|; z3zv(mkdH}(uyDDFLiR-8w8B~qj>!@wSh&zn;$VhE2n&}VQON#;xiP{5+d5AavHZ(O zG_xT*EL`X(Au&6uq=P;zT-qTr7B1%?7_o3U9kLy@aG8U9GQ3eNTpnf!_v4jun-(q{ zWVT}Aa*2l25jNmuXZsc|oF;6=!sS005-nUl!;t=rqA9m?~Y92c~Ze7bda|qa+IlTV6oVTDY`=&U_JnV&Rg(^ut=XaOiXvE*$@yg$svFXW_!h zP;BAy5QAeVxpY1L3nTHzOCCKfT)qi~0^j^NZxU&R&IdUS5}p<=gu!#^^YPzcEL=Fg z>)S!gyo;gQdKCf+T7QZEur&q63Sf3{TIPQMzNyDZF5U>TjpTLdmJKzqNS3#QmYaVL zQr`|*HpOoTEt?o{U3NFr@0Lv~Fp(){iwM7E({Z5Z(*C_=)BoVs^Z0h4B^0fTXjpGQbazuFMh&Y*|e@6Qr(Zice%BGYp{W zQ}7(#a@9{57_HJ@8QvbM}_2&76G^V#il&_?J05Gbzot3g;4}d%zV>+8KjG2cLEEbdsGSJ)Y#QS3^2* zV7U94_;x9K(Ih;nNqj>MvR@=UnRGh4p7a#b+3aJar;_epeZorYIXjJXUG{0p_aI%& z-bH#((ovB5D4D%l5q^e|416=36#}ixzC!uF6yeA$(sRT+dkg8gq$g$1Aw7?DZ}vFS zJ)~D<-#;1j0@9ae>qsvqeOvZ3)H#Io1KF>VK8*Cwg47x^M_mdg!^np&;7uRs53(|~ z8G!q+11K00-nW}Y+K2y>{RX0QD0=oRa3k7q$45bIM#v+vga0c0cUP>2Pp9#DWDB1O z#^<>$eDEQ?g!bnxeD*Uw5#mb5(_?(bZQ--j_{`nH=P2WIRJqTnRmLX~N6@(z;@?3z z7`=!^`sr}Yp>%J06r};M7)ARv_>O&_2zNy@3cJSgr9Hffa_l~xOJ9HoH||?d;58@} zj^hU>ylMu8;|F)*V?kUymB!!Fj!my{4IDS_r_kipdUI9q3R*!rXzRki;=i}y2@(HY zj2?@>AD*AYf73gF|5k1d|E=5t|E=5t|E-+25z+hjZ{-&FZ>9|Y&BXX`rVRhhl;OXb z82_z`@!zT#|E-Gg->Mk@tt!KRvmX9i9pk^%9{yYH;lI^aRAX#c{I}Y}f2$q-Tb&9o z!Ek5r-)uSloAvPD>KOm6_VC|oAOFpI_;0m`|5p3>Z?%vAR<8&pje`GHC-C3wHu2xA zhyPZ4_;2-;@ImBA@!#sH!YKY*?c=}IKK_gIW4zyB(wg<~-)ay4t=``cd9EL_ zkN;LD@ZYS5|5khWZ}r;ndrYR{zgZ9et@iNWY9Ift_VM3pAOEf1=;OcrV*Iz?cJbew zhyV894*uJJJNR#Z#eeJaJ>lRqp1?=gxO+oRa|Nl*FAzGNUqz3F!esO3lUXDTrbefd zTdXK=1dQoC1Voe{+3 z$T{yr&Uqhl&ijya-iMs?KIEMDA?LggIp=-IIqyTxc^`7l`;c?qhn(|1{+3 z$T{yr&Uqhl&ijyaJ^?xB7o|=>EK-};gGg-x z9xjYR&b2FqQOLRW2w@a*u3agNLe8~E3Zsy7?NP!g{Ot3hVss3hVss z3hSyX*vFae3hVk+oP^5NoUVTGeiVy9@zpUDUmZj7)iD%b{Va7+q`n0Scjihzia!g* z(`b%Re6@k%|BQON-p+P~jL>dZNZM{!NZM{!NZM{!$RPXN zuJA^9Wka%HE?bQSbJdoIm1 z$ifhdGv2O{)013!Hasnu+W~(E=8nRGmj!c=1?|Ax=OT7xEAZ~T&Fu1^+cY z_^ag~1cOjrESS4eRF0tvL0?g+WfgK@?)jo|DK*wR4d%#!xwnbNo%nAlp#FZvYB@0X zVNu|^cFV8v$4eu+7oq47^DrnRZ4A5!<}Q5~!Q9_zoKv1;oG%~)@4|M4Ji>~@9x7%=!(-LCKp$lP?hT_KsX?RJG^?l;>Neu+h3wkxC&p4+Za%BIil3SWep+paJJ zaL0nVtPe6<0+`EcF0a^p{2~OHJHrb3tV9SfccB&XF^Ldh?guDjPjtBz8Zej15+#7S z^piN4ArS)1y_G`tC(Mlz7TDIG_V|~PXl6tF0p`+ALSlCGCbwPT%kVQ`?mP?T&W75K zg1Jq&C&L>B%)N#oY!}SsAhQ)Pcd>@l5&n!JZFjpuP7}5Q=F-4Sz+CPW*C&{}7~Ql3 zbICX`m&{uLa~ZM&bJv0C8_Z=Q+b|TdaB^v8%!0WufzF(V8wJe$J`>8%&9Pk}hfW9P za{O~(E{9A9=5jI=gSl5DfDA*)rGJY5!W;PGC6At9?&XxqGBaj6A~j$xr$NFK%*{zU z=i}dkxg6hj;pTZ^DSQD4P8Sjvu3w3phQeGl`y?QhVZf}in3Lv$lA~ov6SkzDL1fqbK&{P8m8p{?w9;Qao zShjEx2!2yu3;Wbjv`?*ted;LMr`Ezgb<_yV9%^BqI+|9W6*$(4Wj%&gpJ1M2q+?g( zC4*PXLE~uj&#TZHj+=>P4qmmdhQa4>Q#$x+5B?SNYM+AIg?albJXrpgUz)_c{sCZnD;oMaXsQ!>Z3#gXZx} zuztJ*@i^;8K6&gFihnttDYMW0AoX~rs&jtqkkU9M1&nM@gb=eF*DENu#xXWMJlarcC!9xF3gd;J=0+2-fn?9?z6n zcnCN>o(a~Ew}X*GlwkeH1u19!NXA(|o{W#u^mry%KQeWCJQJ)R8MHyaGKYMDJ`XT1 zSU>*Jg$(p74jJfI9P&Y-hRoxcVEuRuqA|xaWtLZvk>iqA&Sve5N-CRjf*mwG%CtRI;$J)Q~Hk9=h2c&6-eQkA&PSoSoM z_IRdCtM3Unq5F~j*Q&oHJB;Z5Yt>&4Sygrawd(tX(f!w|zaot8zgGQKVRZks>aPi- z`>$2sAKrzKb^o>MuZxfFzgGPXVRZks>Te38`>$0$AdK$6R{bqubpN&L2Zho7*RYhz zwCVn9)enV_BA)58|629Kk_Fv=t@;sRbpN&L?}X1oP4{1`eiZv#p_37V#_GqyN-(Up+J0i-k1c0 z{nvg)9}4REBpMO5@hQ^!y!wgo0z@c&W368pG#b0q=Wt7t+NJXD`iJqi*s5WXbwAKe zYL`l}_^-A8uuDCf{%V&>aiK2P6Y?u?!6kFOl6isiatnl3Tr#&%7{w)Xi-hSP6p2gb z7KaxyAR4$1N4F-{rzdGRf=j}{RVtF4$OQveGI}Bx3|z_RiCi#nC8H;D!N8SFF(~px zE*Q9emr)GN{UyAXQOuwbZCF8-AirQ2XjBN3&i9Z>36mwhl}iiFgSLWPrO_EZocS#oXMRh@nctFe=C@>=`7Iy3Gry&eGruL{%x?!*axKf4-_pmK z-;#0Ww`838ErWLExAbx5w`838ErWLExAbx5w`838Eg5Hi%b=b4Eq$E%Eg5Hi%b=b4 zEq$E%Eg5HiOEqVHOCM)`OU9Ysl5ys@WG;o-5@s+kzvUVus?4os8T$-4d%BOAeMTHGS#NR z0}K5FgvR`qqmAsQ*Z(+v=c&8t^}lE`wAK9f!!kBF^INjk{5A(A#X@0zOU9Ysl5ys@ zWSsde8E1Y=#+l!eapt#VocS#o#X@0zOU9Ysl5ys@WSsde8E1Y=#+l!eapt#Vtobcz zYko`Gn%|PP=C`D+`7LQ{eoNY!-;#0Ww`8pOE$QXx99X(Eza<1_%x^m}YRVC1RZj`Y zUE`{L%%>wqlvO=TUEIo<7K}z9&!wM%DE%n@9OehwnBQ`Eujh$huR}H9_=2oyV!e^yctZq&XMNk7a-a@I)*h^D9i*nJ|qU zQC2wMa?pbL73S)co=21wJe$oDzC%+HXD z`4!g{C|As{=pRv5T-OXAV17j&QPx-yvOEgK#=3AS5+RshV=??C(xXR|HI`%tBt4?6 zagZ>2L|NltVf2Wy#$7_@M=`&~4)a1%ydJ?cc832AuMEQ%%&&1_I12*7{2G^7diS95 zNTC(;E3W!I^ab-Pt{%bU$j9Kt)y=3Jiun~+PXn!(Uvc$9(2DsLSF=Sa=2u+JhNPHZ zaWz|wVt&QdM0yqTE3RgHP|UBmn)RNTA7TgQhyQxER~BbGXV+rD$zd2s4m^uImaHii zcEDdTzvf%QQCL_K%&+;j@L14_`8D4WK38H_M$E5yvnf0tQP%u!ingj74vI;I;=xziupA^ zBa!M6WzGH(WzGH(Wz8>278LVqel=`E0E+oF{~;U-MlrwUH>A!i4T>~UZt{;PYsyOq zZwd1&@`$pgVmJj^Q_QcaUGljDm|u}r@=cxL+BghgeqeS0^DFX*vZmd``*2$!+cYg4 zf2qEV#vh_Yx5X+63t8b?}>?uy2f)+5TI38c*tWzodnX`EA@WSqqOqN()P zC|F=aJSU%AzjPCe9wxdPG??pR|c{0cn%Zg``cKi%6Rz%A&Iif7Ol8iZ`EV`OZn;uaX zT|;Jw9#IxuOU4{g7F|!q98nhCNX8sd7Of{^jwp+6B4dsyi#CukN0dbyzktjc%rCl` zjKTb(O=J}Fi$3us7J*=X(JhaV)+5TITcvCi^NT*ofCD|EEV}JQs2R*J`g8{12&N+P z*2wxGvn67Fphd{XFG6B|R>)^1LSlYa$j2l?Vty2|C%W7UYc;rymM7*%B_@p-k~@j{ zQON#;xiP|ew)Lkyo;NWY;!n(vH&Mv!=uJB4<0JBy;U}11bo)F6Q|RBE3TH!2Fu&%s zPMPG0vgS%*^oX+Nj4)Y@2psmS!Y164;f;m5=KkR|41t&*&WIg>hyyvI42Q&$(Id*5 zBN=2AscW`JlofeIS@V!^v4#Z9k0BBBYxa*QYxa*QYn~|61QXJ9i33YxJff_5M!1O~ z4QZYouEq32Fu&#lOs;rD84i|RjBZ*nzve@PQOvJ-xiE_PH6JO{3O%B%`50mJh_dEY z60%}`&8LLx5RGDf&1Z?49#PhOt|YPzLlFxHm>>R&-(?!l3ts}AIS)6Y@Gc6!&x8{5 zYX;_rv?=D-d}YY-Pcgsd>q8EiiupBvTqZ-vGLI;0-Vk1m05S{(m>>S@-@qR)dGvz$ zQOd!A^Cpp2=zNgVAmIh`lXT9FiMRr`XpP!&I#Hc*vrE5*(5lN)vNTxAPYq5Lr%aA_p5QRlBvQyo-w zD|B+{srWZg)!iU1RP|%f2CAZ-g{nw9sOotz4yxi_!xpNN6k4dNks(>AO44YdDhB4D zDxL;_B_{mW5aHG@eCyJweUPhdY}7dv1H6N($T+BqUm`oGim7u@m1n56jg30JkmrV8 z$iAW0Ti&R19Fu9Gs-2KB2URTxW1%V*x`V1VBFPS_`ZX8_Rq>HIs7k7mLRBOSu(3oz zzIRGj;{?1ezjsR4+d8Go;GRWqm)FL4m)E8TP}6?PIRLlC#`5LQ;WR3mMzQ$wEmr)2 zriEPYQ8Z1?-zEsQ7BazreB->gwaaVCfMA0Waunr$D<^mLn{yywir=XLV84CHyk;zS zK7(N?_j_To`A?Ej1E2o+|0AOYK6U-NaEsda6!Ez6!hX$wBCkQqf+E*L zLqU;Wp!-L>c282W78LmalpH8R#(^Sa94JD@fg)raC_=`8B4ivWLdJn2WE?0$#(^Sa z94JD@fg)raC_=`8B4ivWLdJq3q%9~y+JYjaEhs|Tf+D0XC_>tSB4ivWLdJq3q?cpF zV(AV5DAI-=zJ*8W=$@o4JW5CRByCYpgioi1N9j~OOI_UR8$#{Lp=$*GEGV)&=z&ML zJxQBRK|D(!8-$lmkl2&-AaDj0Sq0L9A{#+(xhE;578GGh94PV`c;wRD)1ro(7uWI+ zf+OKX1Vsj5+G{}((hd}91M}B{B5d_)2vtHYCMfa^#FrV0Ae+YFZ#FL5tLzTCXh0Fl zcj9}=Y7lDUB$T|jSVO4AR_Pk2B$QFQSMqljmD=!(?siJ_K&m!bpYK>72=BAP7p+j2 zt&F)7-wh4X`Y`6<&c~(L8aefYm*~uOIxfLhXB2gqUT2l;G#z&i8)ZxwB zfg)@(eS;!bL(PFAs}O(#MHuN@07aMu2a24H030ZCJ{Sjzu+A(EN**Yp`%(fFVF(Sf zt7U`iYS|#WS~g5a@0@CoT`e1QSId$CMQ*?i=I-{8`D~C~EgNK4%LduivO#vWY>-_o z8)R3@2Hn-NWI&N0#bJyNdl`lpLN&;)mJPD2Wy5kj>{Ns7YS|#WS~lpemL&s<48&~_ zL6P%7^a+ZvlSN}PpvZElWvE*+pvcXjQB&|=a~J+<`3J#Ss4gV~iaa1Hk5J`lt5VA< z6qF1o^1NugM2$C{26GgY3@DNXLXu0@;D0CD$_@gdQI!lR(jf|?sc<0vc!`1sim)~y zkjoKnD?kzAK?W3gnLgRi;x8IO+JYjaEhs|Tf+D0XC_>tTBBU)SLfU~M^AQ)~oI*gx zfFks_pa^LTijcOT2x$w7khY)*X$y*wwx9@U2a0@KI*UwQT6VRJ zK1imRmR&8Q50Qz|va4lu?t_TO>}naEN1y3w+0`;S|HtsrT`i*veg@j?Y8hP^z{bVw zY8hR`TY{|YY8hQjCY_aCEu%}wWV5oXWppW-{#n`8GWrOax~%MK8GV#YF)O=TMpuxD zz@Sk^SCSc+m0c~PtI4!wWmn7S8Ztw&va4luEt%n2+0`<-p3I1>>}na^NM=k{cD0Pw zlbMi}T`i-V$V|%0u9ndTGSjlMt7WvY5t%c)T1GdMF}qquo5WBtn29m7ts0pD;H@*u=Iz#p78} z%!c>_6rrDl#O&xzI_LuwnFo;pMg9%JLler(>Oe`=AJ?31y&2$$%mi2p}RT@*{@CuN?u3 zXs!$>au0?E2a1q!pa>ZUif|xtpa>ZUiZEmciaf*k@=fR?0E$q}fg(&~8-^klPA<)i zmH6TVP-HIX%yYbvpvZVkKP)K1q0@mP9RD0B!XeXvBAg8M$D!v40-(t685~2&rT4;r z)4}-TC6At<$SY82;#`*VCXrU?e2~*1;R%Y+TrZdYcl;L(D8li5=vT0K6TXUM1!Hi9 z>&KLUgOD8x#NvJgFg)xEcZ)@|$f9WXSoFLRO^QXY8`0!g)E@!!#woF=)re*X9X3X2 zRM5<7D1npkXGc%Lm?P=>71MPh*s)00q2|WjhQmY)i96lMPd4)1jr<%V|A>)KGV+U! z{8l5MY~&v^@~;^A6eGXE$p6F0XREve3uKZWO|=Sx&eT*S{r=Y`2iY}}^k@J;p;g#W z^6RXqFD^%4xg0l6Lq>wmUooGbycEhui}F5J`BPM$a5$7-gr_P$OXVw;gC8Nv1g#|G zk5TzVDxc?+U!(Gw6P)q}t9%xfH&A)8Q~pmXzc1^QAGOLyQ~6OUk8sLQQn}|R0LwHP zuUqB$RDPYxfm8lAmG{`}lv%GN&9aT=&=pXA3Z9a|kxy3x5XM!SH_}>yl@1zZt-tcH z{<;bkI2|0a2>%MC^+#zFNaIYJziY314@i3_PrRcs%65RXsdz>Dy8>yF#&;4(I|Vs% zKpL5M3`p}ro*Q~0|5ZTRIZWoe0i;=*FAw{ukFk%22apQx&|Wkr++78_z8j-qzk?_i z{|Br;un!)4SFhLy#d5;kuBd14EcVf4un##zkHEwYjN)&8SlaH0rGb;SyFo~a0GRkB z=xqZNzl4SY6BFgBI$(mV1tz`>B?nB9alix_2TYK0zyuiwOptNF1Q`cRka55S83#;| zalix_2TYK0zyuiwOptNF1Q`cRkg>o7X$wq{w!j2w3rvuo7 z>E)RBuykpyu?mIxRu4;~E^hUKiOV2LpNT&UOk4oE6ay0t4YD2n7Iy;%or{J|O?MS*7Qll2AtJUQv3C zN^Kz`1v;l8(F1|-a7yuMu|5#?2Q9)WR+s=L23zl5=WT$A>GWaDYn_ivu>~CtwmR#b zj!UrBSw|hF_sdSl2PQT_ngk}k4~ezbn2w2$vDVP9T2|xfCV>e?Xn_gR7MLJyfeF$U zm|&3BT7z#0ZGo}YH~=2l@eltsJld|7e-J!`51D+J+7Fi|d56)*4@@yiaS5Z^Os#&<1M_mPaFjiC-Z- zZwHuQe#(G}rt6U}025cjE5q=uwZ?16fVI{zv;Y&NEiiE_(%A-X3QH(&0hqV}Y7Us#48{QyWE?QD96>u^f^DX6 zVB!~0bHK#?2w+En31-0o6Hg)l2Tc3`Oc^lI!`oSSuNe64b~c`iNXh|@NxX{lC*3IO#BSt(psZG-bUXoV1j4cA)qw=JG1Z$1g$v6Th`WJ}VIdn8<(@O+F?O z0+?u_kUi0KE38!|CQFn6Owdp6WQIftU}6D<>`#~*BWz$>zu4oMA7(@R0Zh^Qt72zWIeTG2TQxAPjXx$^+r#;av$ z=SW~Cyap}|CSwge9jse|e_faEMu=RO&H~KgZ_rKetxLa?>(ZN1w%b{k9)OnccU_m3 zG`^GT(hHCyw=PZQ9b1?7LY^CXA^%nD(uXsd@8-JnbBOLETvX-)bQm;v>(s?~ow~r4 zCs}(o>(pGFF6ufp#p2J^VzYZ>M%Ju#omv)=`HlWmOw0Z@>(tL7W-NvOHoS>ZyrbXf zH<@qrXCvgsA-UxhzXy?j0$o&Yg`A%e^y@ls?;v-CFzNjM^jTTKz0I=u3M^sej;uHf z$&2zuGDnG8o9@R-B`Gj`f52dymQdw=6}K}kF1w!wg}?o>dlO=j{b8@R>A|x5he2<9 z+5I7C=(2lJDy>^~Cu^78Z-A0pb|>SO-O0FRcQS6-os3&{C*zjg$+%^AGH%(Oj9Ydm z?jrrXi)Mm#_dCtJ_8K08;TD@4U^jdnG;d;AA&Tw?0y#{cG;a9)^2Cnoe|n)chYv* zowQwcCvBJA8DyW!?w#Pbhg2^y9@4Amfe(J)k%LrGVlO*Slf7z%?H1q}y32hpJYf`-FB!Z6dk zap3TV?s=GnXIBo#P4oGt7i3#HK=+bPXJ24o3rJ_PQ>n9%bpPr(*Z{9#5$U?>d88MU zE@n^Wy~`M7lzo=^%PAk2J%;q*q}#G->Z~9=BuM=SJ&t%BH>7@#!KnBRrZV-|P>|mi z@=8j-E99>!{m=7}-dvigPR+*CFFr%R0!!>ukeLP}N5m9=6Z9^ie*Hr zSVpvZmJy9hc_6j`5RHew0Mb}SG@h{vYm5RwG@f-O7ZYW>sK#~d8WezNT*rVFfM{Gd z1L;rzqH*0^&;md-uDc$$ie-c$)iR=S-R+dCWkjRdE=nvT8rN}=)B+Gq7Jz7~3!g%I z1c1PHJ2nsy199|a(qI?U;f0zhEro-^TJdziY!}tI`jc6fPd(q@SM%F)1t1z% z{{plE5RI$Zw*?%Yi(YTsDh5`_ctJyOs0MWRbJpcfRYQ&yPGYxV? z42x5b{thALgao}hG9&;5mLk3Ze+3|-Tf%SSl~(|W=(e!37D> z*%TfvBcjg>qm~iTJ>j`fQvf3RTF8@?6@Z8y6h;Av=#g*^f>r<`dOT$Bp#VhWZxdewW0ElMYE=p}1n)4Du>$gy7fZtHP!&b43Xq^tME!8TP5v^(&Apit6%lJM@(A?cF z`D_)-h*q(TXcfzdRKx9exB%s{jzKVj0mYmJzLD z8PO`15v^hw(W;gaO=4)fd$<6%HD;TqgmIG5gq z8WWucbEE)7^9RBiqA?r)EgMmP7g{X^Ah1!#3Q;(k3g_dGmqx_#T2Y9HK_Qxl5$?dY zQpfM1A^=3G^JV&oWkhKNX|;?fjU=s>5v5V2)iRQa8Bvk}PAwx!GQg>2MCl0X zt7SxKC26&cC>=>!Eh9?rBdwMZrT3Fo%ZSo3q}4K_bS!DLj3^yXS}h|=Cy-Xlh|((3 zY8g>lO=?_4l5ZJNx|BY~GNR;LMwEQZh>~v^QM!`%7|V!~Zy8a#hCaqJqU2jflzhvGl5ZJN z@+~7uzGXzow~Q!lJP4UHmJy|!$r#Is(k3$Zi)BRV6Z2UFVi{4og;eURA_00>rdd8y{(7a;(Mr>&6BN`wF)UbaF$CJ_RF zNP{l0C+e_5b3_c2B}xDw=qGV7Lm~tKu_uM>Pna7cEU>MgaUnzkK$LEO0l_r(k5VD+YXpFZ(mG`l%ZR8_7`2RuGQwmrBA_)yRpGzko(ykn ztc&`Gqp>6`07T?(7Zv&2MMaSeG71|+cDpD6Afh4RZ#ATj@HB=*03!0Yi;Dd1qN0g1 zO)w!%mw^nc@dO~E8R1j}&^RQT9TqUE3jh)MmJ!jy@VB*i;`!gCp?-)k3P425g;4+^ zI#Q+;Y8eq7BaB)`M5`oZ1t6kR!e&IH07T?lMnvaIBHJ(&v2ZZi!oL6z(RtyAL1zZx zMikyf;jv680f^|bkVB^e5Yd$($3F!iqU%ErnF>HeAD79H0U)9c;V1-Fd6P)Z5iy(w2~Pmx7CeJo`X&6!5i!x^3XbnX`PLA2RHo`?1Z~59 zfVYkC8Kg1j#TBlJOv7uy24JImNM^;~d#=1hlcYE@o&9OR^UQ z8K!jD%?$2Z`me+luAfk{$-kD#ACFr{N%F5_@_WG!5Aix3UcUR&qNF3DC5XlC(Ahn*u%TUZ!;kyn|#u~0ixN(MCE8GOb zZ32h#CA<{QcoaBP1U6hh_WeOP3&90{6n|_rwo6SzE>+V~v!J;U)}eM*3<+|%J##5E zk5m)ZFsJ0E=H}q7DLpZuQ)#?0&&&)JNmWCbs>$W3N3=MbcQ;K!$>4n`mDMoF_A_kd zoCdPFT13WR`@29Y8A#p)V$^CH!(k=LYbzznI^KrI7>08iD6St2@n}dICTQfiZ?Doc zJk+8QAQBZcHiVK^iKfY95b9ViY*ru11@?)KvtB|V%!3Pcz+jYM3lpXB4>W>};;u(S4SQ$_V^c>0Cdcp4Nc~;{tMyM6h z6*G~@@zw*A#Zjn548AP26TQ^pj@^t}u1sxrqlSWK?kAP2v6f8sbdb_1=Be@)u&BKY znyEG|mIuKeUN+_F?#a>#g1x*_6Zv#cfX6l?PC%RZ&x|7vg1y1GhBb>1ZcYQcpnbGF zP~t(b?H3^xQQ6uiO$c~EB z#(IXa!)ArPW0)1~7{}Vqc^qZ&C^SBYZmmAUf|(HC90U`Sz42~#NZUOga3*=<&}6Td zm;6of1!ioJk%4``j0ygTxu*@4>DWsdygX~#FczrfN{)Cl{jy37%NP^JHt?J6S*mV^ z-F-|`WC7y-eZ2w%i&4Rh@@VU2Mb81kHe!_K9Ir@FPxklkOeEw0?>JAApX`b}*xp9mg1*6p!Vk7;kg7o_aH1 z>AJkGXrk>)WUd=G?nGk!*)AH>q(qP5cV^PLOJ`=%DuSud$HbmVnr1sG>`^TRWtus= zw0Q2nm*2{@l(G4eeG=&5;+xUMA(y7#!A#d?nN4$+A50=c`@{`CA@{pGWOTO6D83ho zZ_yNC4y=z_C(P*J^u5N7Md;Y@V#6*i?h)9Q-s=_q`QL+G-DR&3S3o}P#G9}kPLlmX z-1adm_B)A0W!%-&ax)bBQyWAx((^@CMUUY3C!E@N^A?%fm}v~|9b4YLjPnKPEo}EP zK^uU+Nl)~;joqwA5bSQU&t$T5@K{7OnF-NJ)s%Sh#SnJzV=^-?69P*U8k! zb|%xczr#!LRyr`g4YN4RW6^)g9pXQQEO^2IM+4Z~lYX4+~S%9R!^4xLHV-A55Yab;q#>K~LO?C6wm7g2tj~ ztfT2EpZ#pn(JiuTFpF)Ex1_wsJ2)Z0Ea`2o54`s-hX(Pl@GckEX!e~WTnjE=mwOA{ zo%S+gyv8h3r$lFmNs;Z_++yHXrbHB*Zf?s?j)9HDTG8`}O@h*REgQDi# zChmsp>_%Se%={+q1o8Uj_aa`O)mM*I-hUiq0+Ls$dC6H5U(;MC)}81iFi+}92+(WH zj|JQBLSp0~?E?#y`cjoqeBtkiCYY*^VtMQDR{kPYlUcCAxB@i6JRlcZ#AO#OGsY|S z1N^Fz=>A*cn>mCJEU(6cY@69h>vOBE&uz9+va$~L<_GPG+O@MEGgXJg5n^q~_brgZ`&(!)EbV2B)|8 zCgd+e4|ElxeCR~$^;^nLjEEcP$hf)ti@FHUThzsp?jWSpjJK$MSQoKxMVJVb zwN)?kXf_kPJHeveGUr&>bw!DS;j54LmSxsO^ld58K+Br;l(+%12&N(!GvQ|^H_cB8 zJ1|TioIlj}bWhrA(|g51VksDmdr#=IiJG3Xe8I%rCyjR>zb7ChXc0maE8l-i_H_ls z&LO{g%TDy0a%hMH#}jV<)v3-@W=Qo!(GwOjtP8Ze+N3J6b7WL+|aoGg64qiuL7_4fycnBLghY9e-_UmQG0)ccKGb?f%8D`A z+@D$r{a#0 z!%kwQh7EDM%hKq5y(;T0c@dDMyFv0t#+4(4$ zvbE|svP8T0rfJME7OvgQ4pGhUSoqFN&ad{~Vlp)=9{2XKbM$>VIp^0cn4Pg>ioem? zFCoB#-l3PTf56W%-)q%6*1z3Wz10eCAty6Z*fm%?a3nhb3pp8ILQeLjhHabEHfhtI z994dN%<4BaZffF?Y2LM)*UbHoYP1EKx6W<8awRH1#_w%ae$KSw$yIXoP}{+K-y;9L zzeRrMhBUvk-!=eYrhgpLIBPO1^X47HRKhW?HOU)5qW2%09Pa={*cl}U1KSihf`XmU z&y3225W}2pKD(Lr0wt_JcrQCL)5Y+uuT+!0~@EMsa zPV+j(-eCWDgvJ(CY}xt@bsYkqTlnmOTN#QE@`?!k!Ms>aliX#V4*IkB`!O#OJti08 z4`9M3pD%&HP|H3BSzy=97W&T&pO5Lg@Z!V`IP)_e+28A^yxQ`P8BLg%IeBQ?cV+28VXZz{u5Eq&>rCspy=`1Ml9W`G}V{46J5*N&9 zWe(1_Y<`#DVLP`@ov-ie5+Xs4i09;td89vI9~JxQTBtXZ-I1;-Zldh%{H_VC_w6ft zs)??RmM=Z;7FT2MGm(MFuZ1(v2hdn$vOkrc;`J^3QbcSy&}q47&`{KiXue88uNEa>NyXvbQIxMEbe*Efv>&nkkwmqx*XRz=xMT~5lwXC?zRq(I> zy{oPAs2GVAtVE0B`ju5g{Ti;V)J%aoy!PAakIr7>!(xK(;{xY5AZ72Z+Zq5_r(#&} zA9JSeuRhk>_0|Tv-dgk*Y8%VzUsHMg+u;Gw@8Dc1v+Ecb_ss$eumS7L(?E6B!is-W6F+cc@4ICc+aMa z<0G5ZKdDVsVr3T<)zvh+u4|?aqg?$gpX-f|rwp8RjRDI*&|*0QDS!1f71#K}u8QBu zabC$$#YiW5EJ7>?-~E($BMTpbH@jq7#6-dNP4veSuf8Xn>7^OCrg;O`mhZ%Nawl)a zcqg_qQwBJLcaCkiVkTnqztpoGXW|oMOcedzk@xSbfnn9wn=qp1+E3+FF_T7a$ymVaFm^a3crEK=-^~Kg&3iE93emQ@1lTyweUG?Z?Om;fBV9So# z&K*&GXe;G9Zr24d?Th2!Syz^r1e@Uq-wtc7(6Qr?#H%uIU#joWhtlE8#9{Ju@g$ac z#f-vSZfE6(yXi_0tVm2Zpmjt-fZ(<@dc1`>?R#A$9?`$Tr^I2Cil86|7(P} z9kOC`rO>?0j`6yhw~l++?gTv}=Uf21%$uz=-bAA8=Yys%^?O95Bx#nREA#ve$z}tM zM?ORHKg>$>i1-Xi`)p%>s;h#gPedPuE-{%n?MRZJ2l{;nUZUj%+724%6HPb393VZj zZSyvLqUi|dc!duwEDfqzEBiw`{y;w0rKWuGz_YO6GlGSwzgnQlo)>pe3DZ(p81&T> zkAN$LrlVvA=6k)7Osji+K@iw?ZZpy@G#N0g?K@qE&rZ{15M5?GVYXA^?RT4TM~9P! zV}>sRZ@brf&vNzeyjM%I8Yk){KdLrgfelM8g5$j_uFZ*i>^AHd$BfjC|jsQgEP?A*ezwElWo`h@|0 zgI#aNr%~~)4)((+^nP6A<;VV}wUceOubTMGU$-JE+4biE{(=H_e~7mq8p!9a(`$WU z_1^ncU_Xx1xBmEjRri4~@vG|K!RRB}{r6jZ9UL1Q3~@CH9af?y?PB^;)2&No)I{O? z{$!Uw+^e0)bYklu*-wOnVA*yMTCXf}jY#4To`fkkl=LdHyuZPOn#o1=(=j$-FJuru zY#y}LahESGu3H9LhjxL!e|P^5Ee^BFJc$Xg!z>179aY7kh{MsACPkh;8p$3Wk_T1> zWzLB?EXNJ8&t-12Ka*!n%?LenYO*wyG}$2=gL~z}sQCbeaVP90=|kdes!Og%Jx z314ht`;7g)iO~W6eGD1zH9EyVFrG*T!Z8>vM>9??ZOfJ|r$1yx45tWbv~ z#%nZ=WeEXFd53z-f55MMY!CO3wb`1#H1aOuhHG2E-QUIus|ldeiby?;k?X$-a-cPEo7&-Zei2Y*m~t}@coYK;mW7Kv`m(zJq~=sy$-G;(e))PI1=vxL@@1i z6%*|(UZlOD6V(r0nInhjjdKJV_3`4%~-#ih0o#1(M@cI{MnU!dEo@8 zGym+JknKUxWAGY5%S!Y5N?-YgLbp&DVFy7E z{f+mSGNE~EcYGJmNs+ zTe7YYWM|<*xODCkvX{=2Dy8#1mC|`drE~_?^EU2}FTXm9#J8J{`Yy1(`$4o>d>6dB zE#KbQ*M+50SXvA)OF;#^={$Sa-tI+6?M z6me-elUk!5_O>-ncVX)gG)^qncby*Ti|MB?%oK{Q=` z?Y$JW|D&e7=e+6=d67<-zerSsZR8A=+Th z27i9J;x!PgFHmSFc!Jo@vb-I&bZ$EnLG+1QMZ}cyKyCiKZ4*HYJ0WLrr)avVc?o`?7Ni*9xJ$h zg^#nRk1FFTqSs3vi_~0=3$fF=0hiVWQa7mw9X^?4H8~#=DtUoj4)z*ce)cHyBA|CN zoPm&Z;zA1O93!NADzR_3_2unxWsDVitU?&L>b4l6Ete4c5V=TJLgQ#$e!6YAiRae^ zrG;gR@dI$>o6Mm1V3Qv4om+XfXn|J8x^E${tt2Cjbl2cQpmdnOih!ps>W|)a;ys^^ z@gC@V7scBJzp(+`04^kn4g>JJ0q5Ht`?`k^-`f-Wy5|x5&X0XvtK95D_U?_l0r)>eIe(+0OwVe()pcA>HGm#q8kAJlz6)cA9bR*8-VByTz-xDGkFw3qQ)?>cjHP3 ze+0oZ)c%L*26~a2<+xC4bocP1H*bv+6ry<2>H=%}x&kc@_5g@NlRIImeLqAofo3fW6%txD-!r&2mM zsFV)l^76}&7K*5w&ijR&Plutgth+amIzv6^oasDBorfzEtdasCeE}|1MaH^8$oX^_ zs|IE(A0s|U6nf}rvRt0mL3Ek;x@dhq!Vx->0<;B1-ek7u9I`mCGlRlH+IvVS{ z-GbbVfWIQ~bkTW4NEb}(+iiW5si4A_a3$jT1_Te`@*mi-;4jC82S(=(A$#dC2rUMi zXzE@j3f*+B6mmWts~b}E{m+R|I2{+BK-yI~oa30qwnI!9os#+= zyMe?2T*;(Sn?C4meT6tZu|kip5GNv5nC~mhcL^Gf;9>a51ko9Z3klwD1Bp?%k_nB+Vnx{e1$l51L4^&3SD$|!6lKCz`h-2!BLw&2+mhX2B!)=zCxVY zF}Qm-389P5WL%Pb5>s#`lTU5>AUs#g!&tf|{i zMBQ}gOWim&tBA6A1F3_%oD{Av#tej$$X=vZsXLhOZ3R{w%*Xh%DvxvIs&^MX8M?WOZGTMCc;WfS~w!<9(%)8U`bS}e{4o*fCq&_B`zv8+Ml8bTS zPC6eE(!Ki!U?-_Bohi8VQIMLc9&{Lg@) z1v=jo(hXE+gS}jR>D;ZpbZ`VJLRy7vlKPTx%qA&@={y9bBRrTno z|C*xnza2t`mAHw*J8|KmJsNBv#mEtrO+yA1zia2YE)@G*z0`PXeO*+RM+`5f5i)tAnT zxRN1S1-x@ipvEs%*=C+eI7mfwx^YQYO`-=^GB9e>2R)6i5cf2(LXWQycb&1qd|x3R zcb6mh6%s`kog;B+MJ9EWaDIEGI(?8LUm;FWtkB~t#3_mu=KBh9iq;_bQzVKmIymxJ zi-^SOxROOgZTcWVzCxU!3*mXOD0I>J2rkVasmp}(Ge~v%AUt0o8J;Ti_zH0b&&1v5 zNC;hYK8#BqF^ThWCDVU7B-h|V6{T~%D6k_Tb%Stz@~BQ9B+plflh+H+gGHf>&Y`#@ zb`po-O2$rY`XD%8AsL)1^!N&KZjZ*@$4dxZbXMci;w5#WaDMu!P9H?*E5s4T3O&9; z9O0W7(XsI;3ye+{m*$C7KlQM!jk*;g>ZU_q>c+9HhvW`X=%TY($OUxnQz@ONR7!`f zJ6VF?*q*{8P_(o5&3Lc0FMrWC%GOom_FDaamx3kr04gzTlWOr>;=Rwut83PWG1dePd*odE?oYIaP%O&0OCR} z=sY51FP&#pO6NtD(s@~>bY4>_o!3=Lrydb_V;95!nD}ZyMO*c?&*v^A@EJ*KZx533k5HP-v{#x# z@G!>cbFqouh?IU6m!~xa8q;wl>e;>!?2pT@XH#(Bp12Z<`$N!$%U7&NGMaED6x$&f zipy8T4*A&$<%;`3Ft=Q|1_gbt6m}P#^Kh|ZbZsDYzIxa^E(Lpnis-DurMjd}R1d4$ z26m2$=qwhpm(CKE(m5EHhCqtJ`^5)#8ZPFG?w&%A-9UG`(Bn4HohkJA4RjeqMKECp z=ilj|-;-6_x<}J!v$oZdBUW&@8}Ez?0t#+;6p0?-3P@V;zEAtFz#f29);vdTou9C4RpUJ^tcUlpAvff z2D-e{ulN^&{}?U=Oy_PP7tpy^rF6c8D;XVcyGazf=~#uh_^7a66nf}rxV?0&Zd{T! zlSo5My7d_=^1ChOGM10?=uF-&ZtKfpiF17- z^w;2GTIrr5^w0Mu$(28n+3&l<6r$V|eg1(R7$^@yWb_?QfsH`00zAZTGCZ3xM$oiHC zWaVB!$0EM-B^h0GE>x1v4MO(P`M65y+=44v9~r_aqR>s}!?^I8U!=BGP; z5v?^vx;Du8S+0Tf99&2z9R`K(C!a%^FdW_kA3E0v*+oaw=!#$rL^IWw&SAJT*`y9v z4?0YJGC#a?A5rM0WAE(V5Z~GD-x(+S9!!@Xl__`^o$s01bJqq^&#DKV=bZ_xRqWdx`?_w9qWh9J zd;{!5TNAmiay>Ne5Unmcn{jE0k-AGgYyzqKZzAfZV|BYX#Jb(S?oG+tH*M{9dk+=* zOpC8@+m?Z<$aO4dLgO;kqVq9a|BtlvU>__mkwq7gWsyaL%JNqhkwsJ%Q4v`mh=_s|jVKWxx zi|}A)DAiX{4|e}+^@bJ|bh7g-Qu&SPD>gsEg8QnK-^#uS57zD2nM<_52j4q3Cm$w0 z-oaNh3pj0&#o!^&cNVy8j4wBv?tsROO*Cy``^Y?r*)gGK2(7F*yJ&Hq<#!Na$6)fx zVZihmXki`m)K#&I9POPUW0`j63iMy(bZaa+ifBK(`BS zLw(C6wnLk2FoC^&j}3)Fq;)z$XQ%77j{U8;4=bCr*m*H@I9_!q{7sXkzuA_cJC?zq z*=VhT$#1q52suLo&?0~@OD3;`$?KjP1T?_-%du$fNB6iyEFTe@Ltarf&|lOGWRFlh zilRjn^K*L904OIrJY_+Ah|NZdV_?8H&!)Xl+}R0Rm@nQ2ISeD5Xe|`y23mON21sTc+V~Kd!HBMM7@$gPlQ=ifVkPpMmw6WnKo>1$ z1iWm1?{KOx&+xylt-N%0&~YxTSQ2pNA2r1ymTFj9RWLKcGV%-!ON%(n2y5GnX#EZb zbB7kI%?`HJ4?0_B+xpK!{foCGa%ZXGU#$QcIBNb3@qd>jZc0h32Zw;*5#jGvA^k1l#e_ZY4JaeIs|2f*wp zrh(B#&{d)%Xf1FfY|}F21PwrIP@JwRJ7bqfP#3KVady%oAdB$2lCT<}n^p@9x{}r! z80F-4P0?W!dh2$R0bxxE(GP<)oK_MB^gH0L@ocwXj51~>k%DF z>uDWoE6$v5l%OtJ%tF_Pu5aoHTFga9(Dg$dL5un2x4^Xsxf3SnRJjN<%!e?eeFL1a zH^AieJYnvJ@%KEDx~~wB2t8aF*jwh548UM0(7HvO>uG&PoL#hTgCXvnQ*W@nxf-E9exokUCstC zXLl6ZqJag`eMZvs(0U0*Ihoy4bo`Hmchi~;BoMx9ijE`2lM77Iq3h}rPiFEQ3i^DdDl>WGP~+V9=hlP8VlS4Xh>|N^2DiM)>Y2Iy!VXtqnHZpWCSt-$je@zLsAB zuP&gImX39s;mXBeDPVxfqp+S8=LTByPLR+OV677823nh7ik7EB^XuiW)4_jDLvEWON}LECi#+XO5@XWM17#Wgl& z_Z$p106V7W_yr7g)Vj)wrsyt0ZeUtyvAP0h3r2cdV8GdE3u2Z`iE(FB`K}u>s95s! z=(-!^w)q?c&CQ2e4sVSFxllGJh`QQe6F}GtD3Vq?Okrm%1#+E&U?;6z;_RXI7dn*I zMKF4*(shZBpmmuzduXvqHHTBgK>$? z<;7YArcY~enoshV zpR|BM4@i)^>@uqtC8(3uD=_)3@+w2nD!_?Wi8y;`y+w!8Vz2l}^xk7<19+ZJJ0I3U zady)xhv7|^tWT0c=pzNhB|r<{HK}Z6tqm-#Grt-()W1NKfI&XrS-k96cdGk#q`n=o zFVpF=DaM+c^I_~SVwTh7kDC21?8#t|Bdz0LsK`mX6eb_#Pht2!3IkwTPiQBtSH$VI z2LT_Epe|ZJfx%QSnxf+=?J1d}gXtv3R)Z-YfwFNXmRv{+0&4i?#BXTyh!&iZhX^;>(6^PA$u zv+Ek(h8cO>%ZuI4wDC*O&8L)4I%kxJKXkSz9@W9MQCww#=JN3QPHZvMk-~eV3^?zx znOHk-gt$H6#k#}K3v%yQ`EDNDSZ;k$v|F;TMT?y5^K%X&!WI#5&aqBw7dxFFF6#1H z5^IL~jk9OV`6`>=C9h+I#p!j-a>lH@vfOU+QOEq*=fUoC8}>S6b`fU(wL$@M*X^F7 z>!UEBL9}jlBP>!^BP1XEdJS#?hT)xnQT_)tn9uDnegd@t{$3c2wr8Cwy3T>|5x+eF zHsu4*+YjT<^%3};C3*QgTnTME7&JJor(xLO-d^Y)gxseAXc0ai;8O^>O#{#(d_KT6 z2)SMZ&?0<3KzRl9j9@@fX?+le0G(5GU8^H#-R?%%_GHS-1fYwSP1z+W3GN$5mGJ6P zdTc2{XL26Xd`uvFXfY9kZ3#EP{|T74WBtQb*VuxW7jF@Q=1ej87MP;|UR+!d$q0>r zOO0kP1p+XvCalX~bTw^R1n3cfE?O4A>x(LcR>Qmn;d0Iz=cBJ@E4=%n>HOnwdoxK9AOXjuR+hdUAaWdZ1<^%a=>90+i? z2C((M@+3$TbP%l;7@dZ$3v~o7Ce6=`DQ|#5lhCpN9y(t@=u*kyEN0dYQ|!!kE-aZl zMR%w5&z?I)H#6|9MnQPzNsxO?U~z@6`=buAT?8|WlclW3qAPJk_+l^4*0lsdzPi@I zn_ndY6qI=cg66~c=FF+3`?RqH_e^@x>&{~sNXl%4wWX7+=M~W8DzpPKpvBhpZKZ9jBw_riFhJl@o7`E8fSYupn_(5C zXY3Y>cS3<7|4|JE1%v->GXqZ^E!Ef`f!(I$3a3q44;ai)ii z6S5KpQ<0X&B)i*(iAz|z5r4LTo?~0b$8&qJ)3vx4yNPMHNj95kT?wO{9f2u2^dNSR zWxZ5gUWqQ7%GeDs9Er3wZk-;a+lJFab`$av7&I6yjR^#X9wu(@Sc%JU6tVbf2_Djt>dWJbeuKt?=HVgJ|6+PIph~#r81v3oy#rUNl9=y#l(C z7E?*MMe}lSRX4(5($OM+o8PEcA@mUeaEbZ#@E!|5%-sdBLfUC_d;qa8!9bvK4DFX; zv|2PopHvS&#zBI4FodAZyk>*HtitA8Lonnx3H7O!yNuy;$ngc3yiLt32zV8Soo`Vg zKl}w4RE`!Gk^IWth0r-dB-bAa3lH-G*5v{2bz?Vpv2H6ohS=v|&_%RffI)@k(f&0| zo+kJ_rk^Ld$7$jDR{^Gtw_i=|t@^x0|5;@73z)omzJ!2RVEpy82~bb#%&(^nuKS$FTi&avii~~x^?#MpzyNq_6m39=3Z>vi*=s}y8}otn9b=$ zyCdphMEwZH*Nu;uAb$rO3#1mp_`^!!$H#c`hYE|k7bdSuM-cEAFero;5%x76V|PhV z7cIteBzZK_OWtjh6Tp)cUW6o9NDl5;WSVU-d3aocfXiY0wYUlXTMELO;2(kkzO;s6 z^w_5BJRM;Nh6mf_hwYm3VBOWxrtvlQ^mE2HNAjD(=8#t{8|bf=4f{VR>V+!YUD1s~ zYYt3)tx6EGSAa*6!&5Lome$iSItRL*(Gj$M;YQf%-Gh)HXaHKwD8K9n_XThz0Iq{U zlhe8z#;;+-=xZc8PU{93Oy?a_bPyIt1`CRPbb|1=!1&tzr5H$x4x)91INg1q7u)5< zy3^B(?e=2bhr+zrxEJfv1sls@;YGVdr3!eg5M1K4t`O(DZNn~rw^V}MDYei9`G?ss z!bV{HVH5D@VDiQ&ktr?=ybFQfhCyS|dQqHi%XqO}Ha34UJOKDdbaGlh66gA#z|uLn zRb@{1!Q^4|5CWLYkNR`)zfcf%4g8;n0g|-70HcQ(UCi0n)wcC~LHWbc0_0(01O1rT zuzluq@T8&+bx7!X&^i|;A87(?5`ZpR7QiFWXCrj4IV=Uh>5@Yytr{3z1YIk21TB`7 zU-mqNoTve4owNr)>AnCc?R`ad6kW8A1iXKOGx~Xnj?;PxMkY8Nge{!lg#RBHU&pXP z24N6H>uPbj!`O@M@?zbgc^-hbNP=mC+&p#x;<9`wFUW53(K2RD^9`7J1}6d zZh>{1cG@zpGqLlX$&%tDxd*D6KabYQOJpl#;kp5Lg(P(;@~|7^(#jnOx)3H0fgA$1 z!Ays#uVL~>`+-MTO#Q|9_MiE|E-Cjx_=@y}+H8H)WqPLv=R&c2 z?`LwF3CT za1RXYMeU^ZGE4#R7Z7x}hWHAsZ)hj2@4yrQTikt9B7a2VJ%23Hf0NUUqENo~6yfIP1jo*}=L6r!PL!>p+{|e$>z1 zvakWXh2G1-ZGiki?E$z|DFT`yw?&Gb7&6=w=Yl$lCfPJ~_EC`%Vm594i=8vGPPtd+ zTbwfus4viB`W6RYHhATK-<#J``))zEfrxm_>l`1Iv?cgx(@c%!a`Zk)keA$*_WEA~ zx6yt|;oDT(Xx{;Y&-oU7U7$GUoQlyiU01|%zA=m;?f2S@4|A5~oR}~99sw58*Jn8C z_l4HMyaBn+RsUM@a-N(VMyAa6H*3MOxaKM9-f+gm{;>%(6q3}4D$ z3!7h3AkO?rI{2B+{%(RJ=-fAC@#3?aY(G9c%LfDb$mkKU`R*(IeB+b;8sl#={!ZiP z8>fsPhRq(~i@Qy*Z-;#>Z2nlE2jM54{MqpN+Ur=G>Fw_cIB+ZE{T5HY2u3_-&&SRI zHs8l1etZax<@0qq`uPkQ{W;_3qi*zHZv1?Qjeb5L)&iRkgE8F;usN2aA_Tf7Z<*@l%0&_Y1#OEH^95;`_E`|N7vEg*v)wVC&J9MnZn@`#hZ$8w+ z@y3^&o&;ii!s!|xlf53gdJ3!678T438B+YWjN9X35x@lQfn zFYHGx5bUJDeP`T-gPJefuMT!K>>O+F}~p^Uex?O7xtB~ABIf@ zcH3X@I=cPt`fFPb!@*jD@vYD@mM z<8RRU!dLy}S$vp(Invv5=E7eCKkLQc5!!NXdUbnN{|7wu z6KCQQ; z2)pzY-R|^TI%er6>F8aExA26ih6y@l7uftCL_Fc2hkY09o0jYLz6UnTwLi8k(p_iM z-HUk6hi74PUfG|9d&lQ2+=^56_`4VO3l<2ruIGc_wQ#qu(Ch6J#x6Nc`>Tz8uCcF# zJ&g1(!Op=RJ{@~glW(Q5X)S;WI!FJ9&Hqz?EA_?ecKFQy+IaG!c0NC4;F8Af@ulOp z;BJQDckTEAIvZuf?HBEAIKN2uB#ix7oegh!yZ-E;{a~LBC%?0wX?~0F z-@({$){Q(kjl*(a$a~v*(yc$3quYgiIC*ayPdD+VAsp1M>C! z&I0-Rei-ugWQt^?nE0}LNd=WFRUoNuDv0mDbx$z$7a z=FR7S$@i1zr{R0sU7)pN8+A+j@}iCq6WMRi1o5d4A#hVYk5Wb$s&uL-sn0>*^h8LD=!|w%O ze;>^KFnmzXhBJTeF=)8QpyBgl+-Go)LBl-;4fhx{++)yiZ(+-$n|lcBxA|MYwO?!a zh2Y~ag0XKx*?d?g_bfC^5O2$|HpBF*Aez3|@D_w~&qC7=W5cb@eGB&-*8f^<=D|G+ z%^fh@w{UM_@qYpC7hzt4DaM}Q2pId=f_*cAFB(h-|65-^$N19m?F0*d2i$kUd;#Vz zUpOD)_!i8AFxqEi39g| zG~DCSaF0jBE0KlpGv&{H9rtn;o^I~dtl!!;J>$5Cqv2l7hCc-NPhg&881`H?oG{;j z`4-FrFx=1i-0s`>ZBSbcsQ&g&1n?=S~uE)1_i@a}_+zaRUv`Ph?D zBa(YG8_pX=4KTb-#66o0e;9762U6jXdpH|T_i~uiVW>!NmELW)*&*kkL?sIw1hx=UK7~(#c7mK*hW&6>vy=d4bG^`g5_qa6NUZ4(`jjC#T__ zoJK26=yvD6Tr1XSKix0FyadDga9>W{EAGp=C#Rum829CKP(JtNTKPez=e}HP?P)*v z<=m6g5Pur(xeMnh!?*{hxyBgo!D+b1E`;Z?H4mhpgyEsIt$*<;7_%_5VV1(!aGSo+ zo+;jjS0ay3z)-(|dvzOL1^058I+!M3c#R2L3;QBpIQ`Ucu=)!&AEsRe(*m;w#)e-H z_jKj5EpCIMyn*#AtPjJ8XJNSYGwwkcTMpgN!8{K`*#gboFqAKR1;)ZrowNMf(R%W`2C!>IsyEU2TULmiQ@n0cye+im5nwIr~A|E;?ePJbhvK> z7XD;%&R&5g#xuEWG~Uy(tSZ{x-V|LQukY@G2GWd)2F6E6$H$_nZMkTDcSp3bBi+3f}hXw{{D*7^`6=UOLsftuz zf4X9MMO9_&)Qa<~DkdkAeYsS0B;7Bdd0^4yk!6usH2pf2k)OB8H9FciFq|Gc_!>-~ zdv<$vpUtYf0}b2Qu`PSbGW^!(`>`$-7dvtfNs@}G3=1fgD`|+6> zn4_(5AT@Q=Z>idQ65E+GVm)2Ht21O_xfl;dP`$z*B}ZcNk!Tz!)xxkPUJL@JB0SqK9_dMpPI z=JUX?jX8`S3=QiC`G9|5I0-;;=hCAocmT-|2~oUuC$^kAYW>IrPLw0*63Nj%c;BMyd;VlK*+3%AI}XT9^SDnX}0RyNGfLqm%a^ZQ5PK+m>*sg z4F`iDfJH$BQ@*KQ4g`)4me?SQI@SN?1ySm$rhtYg*C=o zvoKA)H48I0Z_SbgEvwfoy}0Q$i*9et!b&&Inq}9X!D_Q+$)ac0EG%ewYnJ%+nuWa0 z@{EP;ja|L4Anj%K!Xo8gz08`$Lo&4@a7^Xtx3$TVg#}9}0$j(q0zfu>9Jny#xf%(xeb^}+; ziU@NKWT`8l{w)w#EX@9z;%IFx_X|HOiXfLyytgJ6RKAtqFM@%09Jja}+nm~HU9>C~ z4F+^9RSd922^1BnF9$+M`t@BQaWk85?}}ibU=ktp<^V(gZC4F(c~KGkzuvnB5ucZc z@9v7&Y-K_EmtY_iUR)&zMvB8#woX)IP?xGeqzy@*ahT`FcMq0vfAkqe-#_nQrvEH4 zbv0_Dmw?}MY7q6s-H|Xn-*Q5>epH6QP5^tjaOt8_wB!#QX~~;+hsyJt@rM8^U0Aw^ z*#CDhWLr{j{eLR3xU#mbmW^X`raFcC+afeek?LaM)!a4-5JJARo2Y&VSSjqk*cMOk zB-(2jyuxh>>SCz-ivsUBRrge=I96L*i!`rFo4tQmK~Fu4@}_Mx=5zHd-Dp4F#X@ci z=tjFya(a3fOMgIOz8kQucHb@{et$q(?Mu6KtKA0z5_Eoq8Gc}E|2~&(uI+ne5PYl1 zp>=%*Ddqp|y1qXwo3Gant^L!B#0!}hvmr9;d!C%{kc^K4zXOo*y_Q`PRnVr9>`^04 zJ;pr{S4R={Q8`VWijY}0glcN)kvt%3tf`nEh`MX)!8{l3+>_{8SQX_j5=9p<{poI3&Dyw=W@8?bI*9ZXCBP z+%{QT;kBP+`FNd%-EVl1G93vOs=TAb%*3 ze=m?&=?Wl!NQo;Ossy}j&{=fAJJ>_3m_7}gew{gVQso|Xnq^Ouc5`wwqhyh+PvIi) zr?P{cZWWUwmp_Zss{YBrK^&E0pJ)!CUdQ9B16|rEOW^U=K$53e`3GX|8JK@-3mVC- zEj5{^Sq`b#%spsnxopw~iyP8sU*gel>N~67=dE5;eO8a>t#Q%EqC&KKG!Kfp z(dw6ZP*jsvKhJ}r#d8DP>QSrez&lP{eCpy-V!pItb6fqTVcC7kI!6s_ z_5X26b=P?+TdVH}0v-_6uGPOn=Ygy22h1w_>kC5RiUo^5`yJoe-#Y;JVjyr7*02AP zRq2DfYTDYOXI3EK{{;#cs1F1K;R^0Ce%UEHYX ztv(+NlpS9t9T6%%GrR~$eYA+jg-^eiyS*EVxN`m+`|SWWr932jM%>pIMZ8KLFx4PcSnz>U=rnJX`wf z6c0Blt*d8MVBW&g$|A@Vf{j;~cASHBBQ+i()M!^9DDrila19?XGQ7Yx;RVzI^8yFC zS>5YuVEK$glIrO>4M-PfK1rBn?LDNmG98ccTC`RU=7`U%K-k1$Q|lL6Lx^hlg#A!i zG2&~;pNN*`A z+h)K=uyu-7hM@xzF4gKTh~cFkbsN?OQ0cGWZ$Le`t7c(odldeEz~aV53SdHSzoEfy z7O-b_)kKjKgySIA?-M;0ZW#?c?*^%tg8?dbY>hyae!SWWi8=)6(X~;%_#ju_98w=q zfpMYf9?cS%LC0=&h8OMWNNB-X2;Ti^&?THFBbK zyVc=^CiSgZfn$MmRD-#4YF=_uFU$%Yb9~IM@@`u(>f&NBG@-?d>)z9#zI;LN(rAVH z&a4;P+H_&XwY7Ap^Fvagy77XDdUe*C%4p>!E7?&yDdzpYXa;?D=OEnwxnqqw;$v;< z@HJ70DI#iWcSJ4xm}>8Bs~u9OMAY&c^(h1`|Cn0WtLEf3soXTciE>im3}hS1Drm!j4|JuT~KSji3RBJiCMV{;kCRd7A1Fdy@1YB;y~enzcwfH*{J-;x5Y3olj$i?7uV}QrEq* z9tS9ueS>7_)34j3f0VkcuZs*DE0HLp=*7<}Q=;en3n8^z3Que?M7$LZT&lOC$@1n~ z(U{rv2eMpN_dJl5711cQ$Z9A@xLOfYua2UKDcNqJjwoE*5%R91y4Rs(?r{~s)c7=} zQc(S~3h@~7Q#(S!d;^e|A=QrqAmo9n<2m_c#}z(v5soR#ECu6DN%a+x;oT;S!;f(8 zq|_||PP%{HRRfhko_YNhPO5_H(m;Cq!gEwmXEC@U5X3 zmNp7Dkq<9{s(&n!6y;2?iSQ=~_VVq0Gz@XB!V4*w)nx|}+=EJD%zIRFuWBpI)l*dgI@3@_SH%xRZyFVK&BH_W z1<`^qvVc?Y6+$U4DTVqm8J!DBC$CvUJ0UPH991Frpr4nnp&=1abA;!;VfVLcYoXmx zW9f>_@PC#Aj=vUlf!_&Fbs3nVfcl@EHF>=1MG)b5T=Ej!KZasBY4s0jCfRcy)J#)3 zN&TV_xep4F)9$OG@DNnL5H*Zzce^FF5V@B?FU!<|h^;JdlB*}Mt_0OwE-qOYT#EQ% z5o7)anFrKwotj#*g6|W3ivKQXu$Kk$H@le02Loj4Ufi|DlGr3mxndUT8B|X}Zw2b| zy9x43WMZhW6!)=NEbbxEY`IyO%nw0;rqts*StCOGwI;tP(4Pl1)H@_^x}p67=vnF# z(NLi#j8b1S>Dh`u3gnmh9m(b6NLj2t19gl!HEk&CejI1{%X$J(3aaod>tPiMhgXJe z6AI?Pm-uUUu=>ALk@9e9ZLrw4A-kqHFmD;IF8FKv_Y#&D^tEC(z~AGnFQ6Wiy8@ru zsl}G)bl%EW|As{6Ko!FSFdxA1C{{0uE|T`vTC{j~U;P^S6|4Jp60Lg$_CNJu{|~H zc5$12Y51dOvJaHQIN&vlU2N}pVTl3BmSrk$A(C|}kAw?RH~Nlb$_p8FE=&6-deUo# z7Cq7JEk_g(?a8S7mm_a!(TqC${^dx}*2|HUBFhn6x^CV=#P=ywO<-PIxXw}qK2@Rq z%?Z2<^L;6&@_G`-lj-UYsm&Luqa%yM3(LYhpJ-#~g`jXsT`0u&+t9cxQrLha{OX+{ zRUQfBY7L^B81h4>MjcU8Q3|%d{G=*dAm7ALk6_t5CNx}Ib^MuOwS0~0tf?$p5H4f6 z*aV15+8x6Be{eTxgAPU!;C1YvEP9Ld(jD)7J&~0YT~uAeJO{SE1@b=NmH< z2;A$;^kvexs9N8dXsK^c*!!x(ThYIi8{=Z>L35#hsEK;81m+KR>vd-GISs9SgQWX! zI2oFzDxA!d{aHZYyCpA%15bFZ(KhW(V?uJ{SnRBQM}1AU}l}-5v;p$~UgegZr{CA>ZIp->^zo zK#7m>s0YpYF#J!_{{zp@$9dFaya7t4WuxrRKZ=H(foa)4nzS!&?a4NhnasO+?+STAO zcEy9+u5xgqZ$M+w2y@*olm`{EcpqepxBU^$rG}5FsmF1HMjg?sE?83;?g-m0INw!M zcLxHM3o93vM%!?{S6N93_rgv1t4`*hTDyR;B{P7koTX$qQaHiHY412QGs)R7nP-D zpxGw|LQr+6Jfr%=Ay?CcPif+IJ|2`>6mF~BSh>7<*&^t_oP_sYRH_CNa+Qo!M~6NX z4)YjQy^nv+;GeLpHvDs870y-XVj1`wG zXKM63e1c_+3%;3*4>0BTy5&bf}|pWmUK$Y7f}>fU)|L3RIm`Uf!vm+u5r=hGW~O zc1F}EgOO!RReud`m$%d|Qb&hYR;fgdsN<-SNVKh1eN_%5e=v*tli%!!KrJw$9zkj> zK1Z%0aILz2XD>D(Kb^%5$(4wv`7J=M(6+5MpH5cS8BM!l+};%?_zyIt&T2y5K;4#Wi z5IgB2^qZ67P4;Cdk-~IJx9$v z0^yB$S>40MGrB2S5moCVZHvO2u!>bgs}`KRxD*QWrDc^TsDVgpR4pv2S*y-jqmHLq zHvb+msJ8S%9dqNEm#X7xYLl15)L2dMZF*hiWBCetQk7@K7FrP*AI|4vH(0A{+d4Kg z#z6Baef0va@SSZdz(@7fD_HOOZjDtll^T2qvbiN2>bunJ-VOD6F?Zw29xp~jD^LX{ z#J@29gfIEHsActYp>v)**qzwHE*6Iba#)exxc7_Se9PURvp~+-+Lyyo^td^h`4g6! z{Q-AhGcF!@prj2?irMXe(9iEUfum~en!s<7Kqbf*A}~-rI?5*E=SkGR^X9f+Wf3R* zN7=oOBzf5e{0i%1(7Bj@_xnl8>C`V~WC!1Pf!Flx{2!+>pHIhee_Ax}z#F1z5kgbF zP1N!V4p!fAxi<#UG;(h$ve;M4d41JGQdlReqypZOTogZ_gO_@a!G8IR0p2b9K9tjf z)Cq>RuU1V16hE$`{>$OP;IFkVo9K0aU{km2^iXXq+O{&P zK7Il8|DT){k;ev}oE5TcJU>&XzIIsPs8V~z!VlJ|?;RHCU3_&M=Ms|}hsMIkRc+)` z6F3M#H+-@hQo(72z{$OL1Ld8FL*{=UpWwnexs&6OSdide8h?pZZlW5DG`z zmkqbCMWZ3>|B(B4AHjV#g*_BU#>aO@qOGygrFeY0M7I&Y@25UK3s=K-1=NSYmi}^A zq%2%@a;y}0iCFCL>86t;Rgu7@Ln|k;cF~W?W|Rg?OLPW7J>9oy)C4&k&7oQs)p8f z{8+s`H(9}}h8OR8I$Rl!Ev-=Dh}u+xTO<`~;~;W8DKe=xtbv^E%%v4}Eb-HX>Pv?Q zR@#>5Hwx9ad;$Deq57dOfL|?CPuYN4o-ZJKyht(R^dwSmk7=~%$M#*a7vPsw`hY{1^FL!KdH5hAYzf?psO38jn%& zs|2@+Oyx(AsT8SO^E1peeA$JMHx8$0)c0aTWZy_V*b`jb<1!axN$l~LoLQppzg95;0!<|SFt@5JhxsEJl|t-QJd%+V1ce%s(jvcP{9 zmoSUe_vNz(pV(c~j(A%eeu-AyuA~FYuqvbX9@n2a_}ksO_sT6OKUS+A!kdlY9(m9D zBIR}+zhA4KL6q&fst#KPe$rO`Ub!uagx?Ihea8>os;?DE-_@#YFJfPjhPe{Fz@9z# zaa`Ij($`B*W23Jo!&K`w7eAA$epM8BryeGSo%T~n{g?7Mz$<8&B6YcWi5i{8PwJ{E z=l~T#ot|ngpF5 z`&HK$2aYj~t>%Ld+8n7Zjg`slsH?O+CPVeBxKdxFK4Y)wM=LqfZZfy@KS1`zIr{Zw za;DqTA9}B4Z*OD2Q9Q{3igym3Q|76w7P2dUh!-)lGrT_Faz9{<_7E9SjN~#mnA;w6 z16fg?uD@_T+1GqAS5Eod&)~V2#-Kkk%}rf>B#6rdT4BYWi2wz|;~k*B4cW#wR=pFP+0C21 zw`%>8x1o2khxC7Xn)g}vJbrU2nMDLi5}Jw$)@%p!(3gGIOuQsdpx*LrY7&xLNeI3P z5@2}y+v)!q_;XR0)TA_nL4uUtHzik%(I9Zkm>!0!$yperA?BJ%V?ZE&=O0i=P=&@2r6rFEkY$ zhUZrJh!tPnI!r{2+Fb-9$?(tbjx0Md#*f%7jFrZUO4O&okAfwJlzJ8)fhkfobhSiE z*ET{*d6=q<0Oh3(J8-N<+$y!ev+_vwuR=U;mi^7+)QgvgWIqgIYFb%f zuTX(f0N)S1mHG>jjNb#kz6kHxu!a5(vd|*+FHXct?j_MJcsbtHoxh7sa5tVEzL@FKP2WkKd*H`Zag0 zxoL6#QQe%?{JGIz_mtbs3Z18~j#VxH6EPzrd@X42N3nZ;by}9lR3`1}ydzWdXojdw zAzqi{YHZqIA|+zo7y!(B3=fh9K_kIN+o!LR%2z`-hN z9a=!%&;{hsA<=<+@Nz#0yqPv;m+F5wSRX3+j*md*y>lg(_=C3ZLHse-J>suvx;Yop zq7(0&NS_;N;;;80dOJgR-VSM+JqETZuUV8L>ZW=Vf}%7L*B6!`Pa%c<1D+TeT^mE7 z?>~R8z2<88+lj)bKBC=;SaqV^5U!BeRi8F4XKmXSn1Bagn=&OJJ)ql zAko&KzeN)%UW>2wh>W7$1cizlD%XniLV}CcT)ZH&MlHl`e*N{K!QzdTCe6l#8vj^u zKDgvBWBm&{M;#RVdx+|uUsW-A=qxa69#1y9-}^dR@b7E(gBA3|1Ajj9jRN-9qalX~ zwFoEP2mwYue|!51(BGQCJC0i%Zj;ATib-9AHN`PkEA>Pc3SuGwKXltu<#Wo_r|5YFWJ$C-^5hiMHT_oFv_Z;v7#?#e9n}kD~gz>RM%a#2C z!gw~yMcFS~Z*Omk?#DGje-e)!)T{db9gT4ha%lgdW$tgpvPP*=g)RZKQn6?@O^E-JUDj|8VuVD(8nlU%U)gy@N}bnWr64P__CCWk88%EBv` zRxZUW@%YFmKDrDcH$La7=7%;eDn%flkB1t3US`(?0*gUXuRH#vci}OtQ`C{Yi`pt{ zqbp3on8`Q8>Ibt$O0-SJUQhlR|oRdvokm6~! zC_>@<0zsYa?X6Yu##O7kXa4#HnrshFz>I8i33lbsV#C}-COwXfGusk_>A~>?%f!8$ z?3QF~g%g+K;KuQ>!Ss+0tk%{FXG?Bya%_MJ3EK!IvBZ`%-l;(Tq9~S4jNq#^PI?Ue zpXnRTI*EiNNH{HxJ@MAFb-GjW5`StUfdhh+vp(LCsBi3P-Owz@LGkU`_VIzut1{!G zt#LF@Dwn_)Z^koDYFj!tzyyiJB(7Pn01oFTa^n+dLAIMy-_lUk-r2ksX_B&V$^#mJ z(YJS;)Rxp(ZlG^uq`z-qGZM4h<_*njdlL0cP2J7$xYN|y+}YE+suF3&#&hYx?Z|0e z|9Po_TT?FM7*anaaMh6PwU#%j!{k1 zhe3cD7xAW(+XfWTFhf{F5ZYAVy0*t@TG!m!5pQ$qI~%H4DfE_xX2$XLan!V_xrw!o z=~^>EV^6!&)YvBDWHO8QLxAW=dTg_=vhkk!_I4yBILo0J9d%eQ^|Gy=*(T#*Yc7|W z&~?m@M{_lIZ)k3+bgV0e&lP3ULu09AXkfT6mI z1hiMJHiN9O(plX|Z)&1an$v0oCR6>BLujFRQ)2zv*0rr@C3cw}R%o4UE}Ix0AK#o9 z=ywtg;xkOll<6 zmrb1*dN(9((bQ;v3ZH~ZRxGc8CfeA*a43`7lFp{b$3j)rr&TXI^*y1A(SeD{S{z*F zQrjv#0AO%pOLawdq9Pevj*zkOirnzzXg^*d%%w70$1|G| zC?TPWp-{!TY^Y*zd^DY_7{vTcRZNTv90L1B(0>)2tvMi(tz~Y5)?1OqG+;2ol6|>8 zzaJ%PxfkNHXr&S4iYAk~AZ84GI3^?k-IC31mU7TcLYopjAaqTs!I`)A^_?A2KC76F zHcs}Z8b&aCot9N=*LP4$MNjH}%Fk zqR6IHb|90U$c<-wC~DeBtS3^bq_Y}BjZ@cF2oa#GplZqOnw(l<(z-U$)9XwoHMtf_ z(A?hK*n|0ub_TVc%=EFBoZNU$X7K9n-c_6)xordJg7fjEf=P}FQ{U=J4qG2h)TDKJ zH4rew5EG!Mm-Q5s9Z-r~YP1nY>5W1Mv%~2@nKG%dBzhNEYZ~XQ#`NHfn*mOrDJq*B$u8TNdr-=id6N*S-M#tv(DJ$XadDaH)iv*MTTCh z!E=6MYldXn*M4!(P0(WLJH5^|Wzt(xnGGF10v7LC*NKh*+E7DClkR7v?fNluJ2Pqa zktOjtO(kvS&E4JWx^>G|V*r^|NU~Us9XUG~%QzYZKtl0RQ%&B`OK9S5jixL~XVteg zukUm^8$k$>PWKB{p7k?Z_z_ZELF-$*<@FvX5Ry;L2HWZRSnAnnKcXNHyMhr3* z(n(q>GajFuLw2&Lu`3gUSaB0L?sDSsMxaPCh}W2$)jgfvvIq$|)FduDKA9QdA}371 zie)Qg5{Y-(gMJ(f&ub6R8} zY-yBQ$}j-?hf;OsTr(4bKF3#TB0VxbG-;-Eb#=8fFqz3<#dk>9fe6-7vrtO5Tv|EO z`g9+%B^iX1ibP!VVU{p4z3wJqX{80Sr2fmKMa;m>>2^IA?*4-4jG z%$swPgew*X?7GR^G?cIjY?(KF+y$NEh-5%03D#la4}6o+mv&X_s&%9)eQCR- zB$~nGfi4>!5A?axNluQAl6ka*0{s$W!%OE?#~L|ZhElntyEL%uri7lS99aa0T_qjd zQ3;mCou`gwO{q1%Z!HpuvMnpPo*M{|u}dNZ9^u*rk9Ftjy} z-gRq1qWra-J044URkDY`HKehDOHw!GxqoCnhtg1o<@Zu-k#u7_b-^8P5VW(fQZST-XTd^E)Ro z{gLH%&@Leb>GQk6G@};=unSD5q|Ukp^ZICOl5z>41k|x<6$u5>Y{_Y!;*=~3#Aq~i z%dTo|Zw7oenZ_6fLzs{StxD34p#qYsAw5J&%aw)Mj}tl5Ur0NENia4!f#CtlmCjWn zzB>g<15{JEUN;1mfR*qMv$6DeKhew%akP!5uopzzjEzEqF^)bR>Ki3bj4c~nKnZOs zbTpxpNg|1M*ku?sd1G}g=x3|0rQX>)iDAlF#?U)k2V{8K0U&*w>|@!ft>{##ExHBJ zgyl%KpcvD#rc3_=95hJ>7k*d7V8^z@;+n-dgCpa(d9 z+-}26@aKiiw@8i>2|XfAby;=>`Hpk9kp@e%6$1f*GXFr1F=EF3Jv)B>Sp>7CuuK^V zCLHw|1^ebsz`-%O*`k|cJ7_6pVn6oTkk=t|j07;th|EgAq_c^EZGBFneO+T)qK93! zEeAFkh=Za5YJEF)2b_SM)aa0;CQ8^dPiFKavSMEp&gJYUU5xutGS@ZC|Qv zGR~)Q!Th5W(=Je)vOpraE{g^o7)~W8M^bSNQ8qTS?qzX&2H84F14&nF&J3d-J1Vcb$N?FM1Qtn6&HK;S?XQ~y z`Po4(AR?4&9-YW-w?()$HoF*PYDY`I7ASzmV6gR{-;>$CYGg7y+-mj?ZY$~Tf~X}k zIgzv7odfL}NDfdWYkCzJA(u{Xseq5O%juU1j)K|J{`3IIBOd@ct8a5^azb}%R`)Op zLihRx62Ri?RvDP&q?rp@1~~nlePp$`;gt?C;w)r_*?j14cjHDmEVLe=G zGZg2#Aw%G#SpF_ZWpGR)*)WX{S>`_s zK`U7vq%vLLGq8rGHA7&Q z5I`L(1RO##T_7PXz7mpJM&ow7q-7G@h>$3_Ot{;0f}C$q`NtY6p$iruJr+@*bmvx? zr*79GI5jaK=PLulP2-?dX3?r2MmJ+!+R!7R!X?_c3>pZlq!0;g88xwxC9E~u2_6t+ z4Dw%2?{tRLhKrj&ZzD3xZpC5Ruqh+X5@zg6TomDgX1+!{uxFMHsbR7p;0{rF%t|8O znyt@_rof2{0;|WR?c&$u-C)Jq%}Di`fUPRWx=;~ zMwg8wdAdotL$|{N47M?La)QMAF?=rTEFe6-742iha=yKH&e@6;65@aCnk5zbWfCV< zjg1}MG5K31f0r>9!?HEoI@aAcHk9hs;LTv~;R51~ePbKbsgWeHMCpx~yg4lJy6dnY zv9G}NQyz~Ur3TW4v0actdrWe4lDj8n3xhQ44KtB2Wt&!xcVI88i-BMxh4F~KkrvUy zbj&8qBPpUMl>wKgd(FiWlP8yEMSs1{e zE3%MIrDAkVrju^KGS^k@q#(A*K!N~}46>GOzyx3uq9nkQu>HdU9EZ$6 z7Eq)TsSDyR7{jS1vjL(6AZdb6vr`5WY~6_;j>I&223ORkKSOB-HWi2%;CccZo2-m! z|NYX8jAnC_{T#L^c1%v+6aA?{-ae&}o1vIqz%h|P1zEGr>5&lzv);fM{}BgCB;w%K zjf*iMEjg-_ve^+KJAR}TMG77gNq!@;FGeuxft&;f5)J}U`b<%Xh=E8;R349DsbS&L|BWx(?)+U_zm!knJBB#9k_u(XJS#VHQ0F5whh6liY4Y zLxEea$$oSI_O>&$l+KuqBLemV8YH@Wj1p-UT@T2tCnggzL!`=RxEzK|mKCP-M{k`# z%~O!98!N%)M*P^o=mhD!_(du7HK2oj9fceZSPl1q@bIWzFB$UPWGyiRk%X$svZ@2h zUeY65oj7I{FLbsDoah@$nJLQSULCHvCk*rP3@J}jyurZ^7ljw3$3{JyVh+x_&YrgB zjac;gnP-T^hd^VK8IuYq>u|8lqkR()Zs)k}`YV_Qp&Cj_eo1E5h$Y`2&vPI24;tSe z3jA>(yx6stfcHvnPTz-DYa5V)*c^W)feKsc0RP&M_F zNQAWa6k(k}<2vG1t&CsJc&>0lpb&6sx6E>1#^8N<2n{J5_Wu3j<2lD_>70tb9~zq+ zfZSbcLm>TW-A-pW7H>2?(r8^GQbyoD0A3qnbln<^cZ0A9WiXI~MNY9wAj>VI zBgmj&km(_?Ka7iYqikDjcaL|pmPlX#arG83G!qM9v5ocZtbE_tSZYM#&|2%DtkvAq z?exU)2k{*Z@wj$?2Z5L=Ju!?S2aQRvq#5i*p)(Jx=XjlR`@bp zw`!I2yuUx#-;x@QkHqOQ5k|7&((>l$%(Oc`z>2XzF=V&11-$224u^D51scb}$}oiv zk`7vXtGZj9p88ebScy=24CE&_?5ykA*a^IeE5=s5rF9iXa(Z0&C9Z=Urfe0rZ*h=; zl~ON+g-xd=MH<3shTK=HdUdiq zSssQ^Tmud4Y>K0&36Oyb0Q!NQ*a@u^a6Rh=J2T@0U`es+tmE$zlMm`9{E={avhM30T48tD^)~<4>ol~iFw5iQUvT(1I%+_J&5Vd-7}r$w%p;8 zb6kTl`bHW8y{{)2eW?i+W?MyvpcVZA8QnAE~g zUrl*_I;)k?xul%cw!Smb+TAtgH23zjR%s`mGh2~BIPBOm9RwLimC5v(VbA>M0 zSfV*){%B1Z5E;>;hWwEpcBxD+LA`}Lr*0_iijRZdlqX2`^y+Y5TN@;i$%?#wG|2h-{ZyTn<7rh~yW8XIS=Y7W zV;xZECNtiO^+1X~i=36XIv}CWZ13nBLnDtun?;88}Ihv!&?QraMU2P*vsM&H2lUZNSvVFZ8#}a0gpQejOBbZ7y_q6zCjG01$9{Sa^ zC^#mb!bm7NCULL;({!47YVE`ds1=#i$z9&9;Sy(XQ9Ov~16qgFsaE1kok z0i~!io3P0-Y+5VF0~)}Lhvwc!_Jyx&4W7P+GqX?T#57~UOe8Bj7vj|eSxJ*9p!sq( z9RLzwwpK#MHTGyA(*UbF%%CJO07HtuG2*<;?KB206VeUOhgs(LQsI5L~z zu1K^QB@8RY5I1|el}z8G2TdJiR+$!HraEYhNOfB^aW)H`!KiVgj1p;v796t5XvFf++!;$yeN=K4 zxsAP^U|I}IdEU4nVI|cwjU#BXKS(w;Gb;^oTEa{>k|NUvLThXdpsT!2mr4jz3F<(` zO#_(8M+BieTv%(1^hK zx+B4wt;IUh*(8CK++=i==5xuh^JYp0HxLA(vqh}F!3_Ca2uKmrDnVdWTFDYk;5{V- zHdr_-Sc4uP)=F7YI_o78ns<;a>!3sel9!R~CVsWVYbIs?1XlL>V6g=csi5698UDR< zm1N8-0ISY+ni^JjH0r$|FCOuN9YR~18X+n%3PfZ>J&H6V*F+|bVwC zEro*wH)XVmD_1zlfz1#Um&-8bs~sqX%|IZizuLvKUDX10NMD< z_Yr@?4DrX9{BKA6xhDThm_OV$@40VxN@gRVe$L#wi;LUtcbTetpTXP0 z-DKbzr)zJdXWf~fbCgrU^4PYv?krp4U>^x%VHW^)xq+2_@WsLDL|__x`7mGR(}Q&F zaI+0BDXP0v)m9tqPYGg1@V;y@ihhUO$G6t z1@XNF@k#iLeB})rKl_{bjKJRnH^;D@Q0L5{CUK{K z_I#(L4sIFe9J1%kDPi7>Ye$^zGx~erw|z$cxdrjV1@XCp_#FlDmlwoeW#ZWu%>M@X zTi|Y-hR!km>4Nmn!*A=(_!r>kw`@Wtzn9?eg}Z)E$Uoow{9Zn*r3Z?Or(MK7}{V zn*eX)>2HCbW1P6tpM<|0?t*%|@raUo6vne|On*7jv(FgsqvabOa+hx1ZiKxDuq@Z6 zeGLB6!nE%Tto4?C5BAmlfMq|k9R8-G7yA=OdeP{k-5e847dqA(YrcBEn`6z-q_AHI zzX|Y`Hqf7gpKGUW_sijb5)*{;%a@-UKYYAXatq)K+uf$0x6mocAiimuaZ)%AZpZud zmjfPCP39W?*TElxpKV6}UGSd{w}0(pT^RS0fwlg5i*!G7+%Ucp{u)U;+oj(PbC$$0 zxMy>4uP|^UfTO#hPHXb#>l*)*bMd_iX^AWA&ocSrICAImx`%{OwDI=+R30ux~8v4%92;OM3(S ztha6dJK@)O9Fw# zY&gQ~jQ;=5&Id}%>N@u?@>fMWrei}IZ6}H;8ko*E4lo$hff*Dc8Wc^Gm<+?r;0(^d zz|2@ovC$R{7)!ie0uO53SSC{P}3{T>jT&eowtCvV0? zpWG1ESk+as1IU^lc^wnC6>c?hzD-ufOK?jAS2OOcb+(&4w(nI=3!#%{pIJ;hC#CiF zUipc?8vX$H*v*bVI^kW8HP=Z${;}gb9p82bZSjdpue`QW|5#RO z>x_E{ZUu6SPcGM6wo1r{da8tD{g5GN0MS;NLQBE1h#gq4P0Zk ze?3;;)pt!Yyj&VLk5xy*GpUQmlBbGQej&VMO8A2I3ik~6_4bpYPHH?00+=frW7ZYtdl@GSJY?t46BEZv?DmFHKbdmOAiy7A9v_$ZjJ5925K z>9dPzp9Xh2oo@$=+XiAf_?aVpFv>hSeTAQZv75@nQR_^Pr)$5O4 ztCyy9ZOz!Tu)qH$_WaU!x96(Eoh?yktgjx*@V*T1ci8K<^l0Cy>|5cRLz_zbp}fU4 zR?2gW@NBU3)%Xr@6IgmDel@t2`+7D}ye_5pHqr9BleE$!t5-c)D`zjV@qAJ{PAw!- zIj_Ut#r-c`KV5k{TCE>Sn`d>~2d8=&J^(g-Re7(0wLiD|HJtnZ-w$1+{h+HCx5xCE zl{18F2Yj~A3G0^XwF`bH{IAjv*0zOhF;71ZO`(jmc5*LSuS>$}AjMaolz3sqS2ukT zz7s52lUF=-kD&smXL9M64Ff#=ULedoDr;j4QL?loVP zuYx4+2;483ufPB9^Hq82GTUW1Kg+4T#zyxC=?}vz@SE1F>O1Y_vCoxWydu4= z;9l6L7oN?eQSc+JafTJ>=(RfXDv$Rjg#vNR=DxajyDZk%ctzoOH(n7q-i=rEjd$Y} zdE?!9Mco)k_1mfy`ug(SgX*v78DpN`RLd*y#Ra~7pQvpgRPE;wSC!-C`&a$3-rHt@BVqpal7`G4G%;wr=hGp)%4_DA*TjNDj=Ltt(74qn z6ZKX7?wS~^O!;6UAKv+EB9?H1doZau@=mH@Y#6L+VEw7^U@GBXQ~wITH%l-1R~#?B zTXS6Of61Q>9&uPYcC*9tz;`-)A^6W6UI_k6hc5wt)8VDy?>MaXd^f}U9hMH-rS?l_ zC%sx6iqDR`GaPS{>K%DU?VC2SY|oa+hu=yszTNREe_w`8pNe8?@%cLGpLFv79sVh> zDsUYCl>Y(8?*@M#ta&9~3O$xokLmZ$nY;IR0o9TvZHO0E3PX(g8Y;|_=XPAGZd*D~Ce=Ck_$ zJxl;$t*H~hl3(ihGvI}1CH_O;5wPZs$qNIyVtU?@GzAD=fMCG9zUK&TvbH7iM_5!^*GEVU;)Ju=pJgi{F{yT@FirkHeDR>#+F89Txwj!{SFy zs%_sEhs8hbu+r~$So|S}#lPgR_}3j4f7D^|d}y5Pb+ixDGu)Kn6&YTg;SqlQvwA^md4pURd)SPd5c z+i?pLinsYU+x15a{2Z|Q&Fs5;r9uLpEQ3EEZ1!LMxzzDWx7^{&k-s#PzuNJVm#>xO ze+}}V%;X0gFZm&ddypRnPop2KzGDq#eyZPAhn0St!{YCDSiJnL_`?B7Qxbau{lbVaBC?D0s@w zjhBCtrDv~LoSmhYzmoCWIpkEb^a~yT7oNtRyzO~yY4e|eT({!YgK z9sD&}dig&Y|1^9*SoYA`Cx0m8)o=2LGOYgJ<*<19Lm4kDKPSVI-{$oDS;`Zh#dEV~ zyQ;^e#^O16yG*~|a`|aI-v;~fl;2WJb6oKw_>;gLJh1l2cgc8-_oZMz-tuKKUgLcg z*pIh-n~c|Z_hjh@9Ix>n%+kyE$K2UgIL)D#IH84t$vmi(j5$ z`AvCVeo-FF7s_K^&{nbX?{ZlAFU_$0oqT%vGE(kjL`<@mRh; z9?SQ~u=?{_e0>b7zViJsEPk`Y;y<5Z`2v~z`{|E^^cQMVo$tcNpAG-Kpeg3sfD%@_F}8L#>@;Adl4 z>E(}PSo~~<#mhg*^L-ABmtT_S?{iqZe2+Z8*Wu;#$Ae(KPqX^U_sGj1%J6}Cwfm9B z<7*|7G!{K|`d5BNmY?b)KO@6x@64tWi=UO@r4CE}N{1zXb%y&gEPoipxZ?b~+hL`b ze@vj^h4(nD@*4FkT#dzWo%YE;Ch{@=R~%M;@|W@awfKG*7T@QvirSyyh1J(?jm21< z^5vW2^OJ9i$MQ|__$7x`-jgo>Ep_sjuZpF=75-JQ&KJ@brEfT+3Uh?v3G5Oud-wIyM11o>0<0XHW!>ZpwhsDbehCf`f{xi<3 z#f|f8^?TQcOZ+#KFRVSbo$vNJ{_o+1J^zg3zXvaD{0m_0S<|O5c$S~AYG?0jrd8k9 zOeubbyl@k&)|;P$_b-g=tL=|oa`tZ$3$O6ZARpVyhx^s`%ZWnR^RpeV{<}KE0}jt1 zy|6M=`SZXd;7(WG9w&bdys*iSfcJs*d6U(Drv@opjl~XlyKH@wFH(FK=c{~=46DA4 zGiz~2^|f?kaZkPcoILLii#cGOr%b;VI$l+i|B;pV*T^pdw>kL%$4j2~YgKvG?*WI! z%P)yPTycC3IV@g&Nr6uM>kf;TpOW#y@>4Rb@@C<8WLUg>l?;pD=CFAADS7_N50+TG ze3LwXv%|l^EBx~=sD1w-9OdJAcA>-1(tpCM5s>~r556Z$FYMDFb^7#ko`@1^j%XcX9vHUiN zm7jcvJm2Lod*$NZtbc@~eC*#AO{Q=)7N^xIU%o|=kLC9{tn%e+??bP+y0|%Xi81yYNLaEMC4zhLwH@pCiNK<&)&Ge3A@H{=N^D zSn~2kGG17|NFK`<$z%Bhna)62)m@c$tFZtzx@ zzNNY3RbTlQnY`M!v!%r16HQmcNk4@)t53`YW3c#f9bk_!jjOw)OYh;0CZV zu=Q6s<`?JF)#sP_{{VU6nL$3zpDm96F}$!otG4xQcJ*V;#^SKbPnWG{@@I;V;(8_@ zCXeOAo7U9?Qqa zWBKnG*7)&0C|!-kFY5G{e0EG;`XQek!$F@M4*KM<_FZ9Xk29!` zu$o}{xY@O5PM!A1N5{&W3;!%wK0DSP`Ro|4{@gsT#Hz3Sb&MC5e~w|vKjP|lA^8ix z#dE74?=#ZXSgfp5Kl$@SfjIwOa#-cbpU3mF=htH1f26CiSY0Q7`TO|vdmUE(^8fMt zj`mu-5FeU&H5TjYm6d z{z0BU?67$G2YG(=c_kJv{~*r~x&FAJPJhV%$IIW7{B!g^VM`r(`TuzNLm6&J{x5cZ zddB5uY7|A6-iY~w@v z$-Jw(rYXKpSNdNApU>yn(ktO+us#nPAi*h|7h1s;-Y04QC;novFYjvbt?bveUW>mj z<2QnzJ+W-h7VrzMe{Rj>{}}xC`=Y;^^1DCdzYczb^;N#S;{P_|p8*fE{&gh&pELd? z@Zjn3|4u6Xzk_!seQscw-Ud%@jP_jo321_E@2_Y0Oz=48!S+;M8+bbzX+Ny==V$WE zGyJg(uK{y~-wjyo>$#J^haPA=HgaSBYz^dp6L|bLfe;o{{(y}*$0j1QSc)4+xQdp!B?_x4aMZ*Ebw!TmyK^T_-)3sE9G|q_@^m9 z)%PP{-`7Kde1C>FWcUv={5kNfYW=1bcY#l5eC5Zd^6v#dg?-tZ@NTg7 zQ%5I6ef~Qzo|sMg-B6rR><2%LJ+c1%KVV<~S2BDA`~>4Mi}Wh*Kfyn6_G3B*`iu0Z z*{3sw86TY=B>%f$pMQIX_5BZ?Uk+A#m0t7lf=Vp90IXR#yX`w+(^6=;r?) zfbZb_*M4}(axGx%-RhnB=& z3?6s=w<42YmEm6Sx5;1QrS@#fczn%@r_%q;Qh(kKehm9*^Wh%wZrZygmH$7p^pAkI zqYtf#e*)Z(K3RL70YA$8IWO`5oTdLU_|20_efbaY9q3$kFS7zeI5Y6$@R>nfx!nA7H-Qeqb_&(bxCaz;9qr#!`MWz;%$26G3JBm^QXb+Xw_cd0`~R$0(b%Axg+I=uUrj(KX@7I{YMi2 zHSkH3i)s53{$?is58%g`-=`)1d8KDOn-YEnd>`-gR)baFe*^pWy#v0A^?Z4fpU!^( z@bx`4!@rf`SsAW?`>D^&l;3$7-wA%s*^|q_`n*gEehT*O8t??#zci&E%+im7Kj7xW zZ5h84d_3bnJEi|J_*TYaAmN8I`M&_qVZBzJ`A42=V|Ap z{N4iJi@mb>cQP9Z-@oq#KkV$=EHI8NP5fqkom^a)$>Td%lYS+*TrZC=)@1zk86E?F zAA4y1a~t?k&XcD9cZ2(BugxEP5sM>kzy3GiCCuj!Qa`On-v#^fe+YgS{cB77zk_{y zkAmO8KYb+e`Y$WIL!LI9_ms-70sKk!C$kcN4%nw}16Qy&(-VJL#(!MA(~n{BIG+dD z{JbTT{~Wl->C2tqvi~O)Uj;wv%KNJ<{o~-T(H}cgefA4uFFF!_1^k9P54r`g}{gI{Jo+j{uX@&UlTA49-qPbCjX!g>L+`BLdG|OFL&$9`!oKm4F7J17l6z2*pYWG0?S|HZU$WC zT@rZf|4Bu6mVO|^8^MpUzp(Sh?`Qm0@F}Oze$IpHFMK77m!18`H&Xf-E}bWKXX*c1 zJm)b9$R6$oA3=Ytyn~tii{MwWXM2%XdH)7JAA4l|Kb8N`_9y6%jaL)c_y0Ly`D?H& zhV`hD@#le0WxkSa$iE95Yp41hdFK=0)7j5lmiPhi9oQdzM}q3}2jCvkwC)Ad8M`b&EfqUde;?tbnfVl>w6V@WP~_Q3em{3`7wf7 z3In5W3y;s+{qq>6V|c|S!vi7FJmMG-Gm5W;PH{?B#6>507sk*3GKrZEH!Wn+1vp zqp#m4X5y+(@i`8GZq|zEoN|9NP<>&ShDKbQ;N}+QRSw6RSQ}4O0D=ryWw{FQi z?#Fu85bSS6U#eT}fw?JTV#|d{a;nKZqQ)qGV5pQrm5nRfuMh#?f)qh{=$4AU^qNW= zU1=R192(@?sOi2NqR71A-tlVSL_+q4r*oBHG<-cYB@x(7UkuIH9#=!qFW$tk^-}Uh zLp|3K;W@@NZ%u#CO@HSrQXqk!%jh;l*X$)9ebsab467g?gBul0iXfRAyJNUGv9Va# zz|poq@t3bbkH7hX<8j?83>i^3hl(49$9#(7^=_Hc>5_$b_}Q7GnyFy%@g7+#(c4DurK+`KMTe7FLXM zqa6!I3=o4-CH1h`K;R>bhCzfPMLkOKpF+HXX1=$)r@7*vCp*(j=Z%hG>qeRv1iB`C zl4Iv5whX1@$aWXHDvu0R#*C^4oKoG(Kt)0!o)7vPLhaOqCCEbIG|z9VR0{i!``T~x zuZ9MT3K3_ZedD}JiI&5ElRHo8UvcFZp2x_dJkGwweTnJWx!Avcv$T zed8-N*HdnbIvLGl0({7nD70^g>Kwvlcdu$qW?a#_qsi$GVd{ogux706ny-9%2lD9O z7G8I5s z)w`>+NO2@gFx6yUdvO_|mF#Kv4RMDNLUj_Ixtj=beVY~Nz9tsE@79&6h)SiUz-lXG zf^`TsI1ShOuzaM}hEQ1-`{-cHtgUN_MIQp=5zBsr;Gry{-Ijl=1qP^ewO8Y@#h7@C zEH+3eue_r>+oJ|pF!<5FW$Uq61ffzjDRq?ip?%{+gn-oMNcB&FyO$Dda+ykTo!-5w zy_cyi4O=n1E>&wmTe?})USOgWZ`Xz}OaOE|glP!*$4+0|#>1fSG2++CuGUyhHQ+|| zg?48I>)X_GW9WL~j@1TDlS~NrkOI-OQnD>#l+K#TlR+SDqcHXtwFkfW0q(TS`Mk4fBYR$6xq1#r5jsq&7&Zd zrbGz!jukjI0G&oRL}--G#3+y5QcdDX#i)aReq~0GV5^FqqoByc6x5Ge_+YH5a&6VF zZEsgdj-Udm&=7vT+c%8BPHLDpEpg|Ua$8W%tzvhCGYuLd!=X|3bs%;aPfVl2WEmYN zZj3~|b)(-_;te<2SN4A_aIWT0O_b2l9=5FvpF*5Q8S3QgTN9xKhC7R$ znIu?|N+qH8ak_SGpef0K=*f+vek#omN~>%K zP|>+%Y{PZe4fU_nGT|(cRYLO&T~d_H5E@>c;UeZ(t;x{Nsl^4qZ$omDiO=32E+}UioAg`!@R8-4XR&_e4SEOXZ;eg zP%~Kq%h}Xf&RmUaj9Q*jp35>F=j87Vj`ea>bU{^<2+8TkD>vO3!bfU)m7#>N#1?rm zW}~1@#0eeRaNT%+RYR(inO=*TUZmYY>$$P1Qs|nn-D@}=F}%xEE`MEg$?6)I>ekwc z=*J1b)o;2GyIIr0T9|ePoS{*@^svP$vV@9+NMNa6VF+47_#~asIh%4!_A5#>LVk8I z9w7`lMk8uWIJ1nZ@?o+r)5@l@FYO#{wt||8URdOykpIj(uc~1 zgSa)7Eu!z`GTwa3VKL*XmEMZ$vK%Y4CZ6{~m^Zq3v}S5vMm*qUDHWz%(?#nS1B`^!*gf(6}INQ;qF5Y~^pu`*n%U)$}_w@BK`9>|u8@_PLhs|jw=f7*f=lBVwbZiaHD8Vtl4WOm5L*e1r1BZGA%Od z@VN098XRW+MhjWF6f1Q7ARz&h?zOa)J?zeY71lsh&Q;RntGXKOmo~a#YAVEaIcTLx z4jmPy99uf=iH2#1GbkaKY89&Q1=3Qj`NkM58(qPHWH@x948-6jPBd=1VHz~uWPbZN zP$UCk0@4AB(JEaoWfk;!(68xi1YB#))TpLqyiVIJ#lB$onmUE^4P!XeUmfA~rqw*d_5LRG`=ElswI#)pO$kFQ^3?Sluy{v*j#N&O>nl-#mHpE83Zi#fh{<<{Io+8CKS&s3{?1)J~k@O z29ZhdN|W#0t_vpEM@m7?vSuWza@;nB6qX4OOio2ue(|$X{N0eY%jCLvp!?trr_ZQn z9>;&JD=*7hz8sdHd|PHA$9FtbFLAm)%8&BXk3LhEoWCr;RY~TT$*o4t%2j?l7adoO z@MVg2DZQ?>{OG<#fJ^0mCfMmZE$CrV2FXl&InOvNxN~g=X2f%hO>QyxCK7A0JF5|uqwtG=` z@Sl!aOz9l=gu9pAWAC3*-2bP#if1mo+6#bv>>LpG;2h(38p8n4%#mH%f zsvm;}*>aTlzR4L=i>3uJ_R2>fqz9_*@%)s%%IB7sPc8QFd7)iaKU`31 Date: Fri, 6 Dec 2019 17:41:58 +1100 Subject: [PATCH 053/155] AP_Mission: added MIS_FLIGHT_ID user settable ID of flight for log analysis --- libraries/AP_Mission/AP_Mission.cpp | 6 ++++++ libraries/AP_Mission/AP_Mission.h | 1 + 2 files changed, 7 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index c9f05dbd5a..c0eb6c40ce 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -31,6 +31,12 @@ const AP_Param::GroupInfo AP_Mission::var_info[] = { // @User: Advanced AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT), + // @Param: FLIGHT_ID + // @DisplayName: Mission flight ID + // @Description: Mission ID for log analysis + // @User: Advanced + AP_GROUPINFO("FLIGHT_ID", 20, AP_Mission, _flight_id, 0), + AP_GROUPEND }; diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index 9034942fba..54a3f93707 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -555,6 +555,7 @@ class AP_Mission { AP_Int16 _cmd_total; // total number of commands in the mission AP_Int8 _restart; // controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run) AP_Int16 _options; // bitmask options for missions, currently for mission clearing on reboot but can be expanded as required + AP_Int32 _flight_id; // user settable ID for log analysis // pointer to main program functions mission_cmd_fn_t _cmd_start_fn; // pointer to function which will be called when a new command is started From 015aab46a4b4018c3ef24f4b58a5f1e816e198e8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 16 Feb 2020 08:21:57 +1100 Subject: [PATCH 054/155] mavlink: added MAV_SYS_STATUS_PREARM_CHECK --- modules/mavlink | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/mavlink b/modules/mavlink index d2cc7dbff6..2a8ee81a18 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit d2cc7dbff67f8c318a40e1ef57a99488b4737fab +Subproject commit 2a8ee81a186853359a242918279dc3883fd649bb From a859f8355da7a6e1f11e4e619ef82d5ec9c0dc52 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 16:36:29 +1100 Subject: [PATCH 055/155] GCS_MAVLink: fixes for updated mavlink xml --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- libraries/GCS_MAVLink/GCS_Fence.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 53cedede1b..7fe2b648f1 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1834,7 +1834,7 @@ void GCS::service_statustext(void) mavlink_channel_t chan_index = (mavlink_channel_t)(MAVLINK_COMM_0+i); if (HAVE_PAYLOAD_SPACE(chan_index, STATUSTEXT)) { // we have space so send then clear that channel bit on the mask - mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text); + mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text, 0, 0); statustext->bitmask &= ~chan_bit; } } diff --git a/libraries/GCS_MAVLink/GCS_Fence.cpp b/libraries/GCS_MAVLink/GCS_Fence.cpp index c54af0d986..5baf189504 100644 --- a/libraries/GCS_MAVLink/GCS_Fence.cpp +++ b/libraries/GCS_MAVLink/GCS_Fence.cpp @@ -67,5 +67,5 @@ void GCS_MAVLINK::send_fence_status() const static_cast(fence->get_breaches() != 0), fence->get_breach_count(), mavlink_breach_type, - fence->get_breach_time()); + fence->get_breach_time(), 0); } From 4d737d798b11509604b7980e467f205af6269182 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Apr 2019 09:33:04 +1100 Subject: [PATCH 056/155] AP_AHRS: fixed getCorrectedDeltaVelocityNED() for SITL AHRS --- libraries/AP_AHRS/AP_AHRS.h | 2 ++ libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 44 ++++++++++++---------------- 2 files changed, 20 insertions(+), 26 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 8eaa95ad2f..e2c9d22a80 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -553,6 +553,8 @@ class AP_AHRS const AP_InertialSensor &_ins = AP::ins(); _ins.get_delta_velocity(ret); dt = _ins.get_delta_velocity_dt(); + ret = get_rotation_body_to_ned() * get_rotation_autopilot_body_to_vehicle_body() * ret; + ret.z += GRAVITY_MSS*dt; } // create a view diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index af46f008d4..f936a336e5 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -1300,32 +1300,24 @@ bool AP_AHRS_NavEKF::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const void AP_AHRS_NavEKF::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const { const EKF_TYPE type = active_EKF_type(); - if (type == EKF_TYPE2 || type == EKF_TYPE3) { - int8_t imu_idx = 0; - Vector3f accel_bias; - if (type == EKF_TYPE2) { - accel_bias.zero(); - imu_idx = EKF2.getPrimaryCoreIMUIndex(); - EKF2.getAccelZBias(-1,accel_bias.z); - } else if (type == EKF_TYPE3) { - imu_idx = EKF3.getPrimaryCoreIMUIndex(); - EKF3.getAccelBias(-1,accel_bias); - } - if (imu_idx == -1) { - // should never happen, call parent implementation in this scenario - AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt); - return; - } - ret.zero(); - const AP_InertialSensor &_ins = AP::ins(); - _ins.get_delta_velocity((uint8_t)imu_idx, ret); - dt = _ins.get_delta_velocity_dt((uint8_t)imu_idx); - ret -= accel_bias*dt; - ret = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret; - ret.z += GRAVITY_MSS*dt; - } else { - AP_AHRS::getCorrectedDeltaVelocityNED(ret, dt); - } + + int8_t imu_idx = 0; + Vector3f accel_bias; + if (type == EKF_TYPE2) { + accel_bias.zero(); + imu_idx = EKF2.getPrimaryCoreIMUIndex(); + EKF2.getAccelZBias(-1,accel_bias.z); + } else if (type == EKF_TYPE3) { + imu_idx = EKF3.getPrimaryCoreIMUIndex(); + EKF3.getAccelBias(-1,accel_bias); + } + ret.zero(); + const AP_InertialSensor &_ins = AP::ins(); + _ins.get_delta_velocity((uint8_t)imu_idx, ret); + dt = _ins.get_delta_velocity_dt((uint8_t)imu_idx); + ret -= accel_bias*dt; + ret = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret; + ret.z += GRAVITY_MSS*dt; } // report any reason for why the backend is refusing to initialise From e6c1e505e3c72cbe0d395389abbd0ca30de9544a Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 2 Feb 2017 12:04:42 -0800 Subject: [PATCH 057/155] AC_AttitudeControl: make get_tilt_limit_rad public --- libraries/AC_AttitudeControl/AC_AttitudeControl.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index f02393e74c..0d44c78406 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -295,6 +295,9 @@ class AC_AttitudeControl { // Calculates the body frame angular velocities to follow the target attitude void attitude_controller_run_quat(); + // Return the tilt angle limit in radians + float get_tilt_limit_rad() { return radians(_aparm.angle_max*0.01f); } + // sanity check parameters. should be called once before take-off virtual void parameter_sanity_check() {} From 5e1a188483372329f3a665adfa66d130ef92c607 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 26 May 2017 14:02:16 -0700 Subject: [PATCH 058/155] AC_AttitudeControl: constrain tilt limit to not exceed ANGLE_MAX --- libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 17a654a76d..0a9feb9fcb 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -261,6 +261,7 @@ void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in) } float althold_lean_angle_max = acosf(constrain_float(_throttle_in / (AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f)); + althold_lean_angle_max = MIN(althold_lean_angle_max, radians(0.01f*_aparm.angle_max)); _althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max); } From a1e438ad64dbbc9095c21e602bab3d229e3d1bb4 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 13 Nov 2018 17:38:12 -0800 Subject: [PATCH 059/155] AC_AttitudeControl: fix to backported patches --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index d975bf2f1f..944de7e51c 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -153,7 +153,6 @@ void AC_AttitudeControl::relax_attitude_controllers() // Initialize the attitude variables to the current attitude _ahrs.get_quat_body_to_ned(_attitude_target_quat); _attitude_target_quat.to_euler(_attitude_target_euler_angle.x, _attitude_target_euler_angle.y, _attitude_target_euler_angle.z); - _attitude_ang_error.initialise(); // Initialize the angular rate variables to the current rate _attitude_target_ang_vel = _ahrs.get_gyro(); From 8534603a73b0552dbe949be166693077a411eb9b Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 31 May 2017 19:48:31 -0700 Subject: [PATCH 060/155] AP_Notify: change compass calibration tone --- libraries/AP_Notify/ToneAlarm.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Notify/ToneAlarm.cpp b/libraries/AP_Notify/ToneAlarm.cpp index ef8b998388..71891cc480 100644 --- a/libraries/AP_Notify/ToneAlarm.cpp +++ b/libraries/AP_Notify/ToneAlarm.cpp @@ -63,7 +63,7 @@ const AP_ToneAlarm::Tone AP_ToneAlarm::_tones[] { #define AP_NOTIFY_TONE_LOUD_BATTERY_ALERT_CTS 13 { "MBNT255>A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8A#8", true }, #define AP_NOTIFY_TONE_QUIET_COMPASS_CALIBRATING_CTS 14 - { "MBNT255p4f16e16f8e8d.p4f16e16fp4d16c16d8c8d8cp8e16d16ep4f16e16f8e8d.p4f16e16fp4d16c16d8c8d8cp8c16dp8c16d16e8d8c8fe2p4f16e16d8e2.pp", true }, #define AP_NOTIFY_TONE_WAITING_FOR_THROW 15 { "MBNT90L4O2A#O3DFN0N0N0", true}, #define AP_NOTIFY_TONE_LOUD_1 16 From a63c06a6abf4f545d7396e23414523e0e339d3ad Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 22 Mar 2018 15:55:35 -0700 Subject: [PATCH 061/155] AP_Notify: don't play any tones while armed --- libraries/AP_Notify/ToneAlarm.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Notify/ToneAlarm.cpp b/libraries/AP_Notify/ToneAlarm.cpp index 71891cc480..85e7f681f2 100644 --- a/libraries/AP_Notify/ToneAlarm.cpp +++ b/libraries/AP_Notify/ToneAlarm.cpp @@ -134,6 +134,11 @@ bool AP_ToneAlarm::init() // play_tune - play one of the pre-defined tunes void AP_ToneAlarm::play_tone(const uint8_t tone_index) { + // Just don't play tones while armed + if (hal.util->get_soft_armed() && tone_index != AP_NOTIFY_TONE_QUIET_ARMING_WARNING) { + return; + } + uint32_t tnow_ms = AP_HAL::millis(); const Tone &tone_requested = _tones[tone_index]; From ad12d26dbba1bbafbb2dc951b04c1d0aaf398232 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 7 May 2019 15:08:10 +1000 Subject: [PATCH 062/155] AP_Notify: updated buzzer tones to match previous master-0.4 fixes jira APM-8 --- libraries/AP_Notify/ToneAlarm.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Notify/ToneAlarm.cpp b/libraries/AP_Notify/ToneAlarm.cpp index 85e7f681f2..bca2703f08 100644 --- a/libraries/AP_Notify/ToneAlarm.cpp +++ b/libraries/AP_Notify/ToneAlarm.cpp @@ -93,7 +93,7 @@ const AP_ToneAlarm::Tone AP_ToneAlarm::_tones[] { #define AP_NOTIFY_TONE_QUIET_NOT_READY_OR_NOT_FINISHED 28 { "MFT200L4c", false }, #define AP_NOTIFY_TONE_NO_SDCARD 30 { "MNBGG", false }, }; @@ -321,6 +321,8 @@ void AP_ToneAlarm::update() } } +#if 0 + // disabled for matternet // notify the user when pre_arm checks are passing if (flags.pre_arm_check != AP_Notify::flags.pre_arm_check) { flags.pre_arm_check = AP_Notify::flags.pre_arm_check; @@ -334,6 +336,7 @@ void AP_ToneAlarm::update() } } } +#endif // check if arming status has changed if (flags.armed != AP_Notify::flags.armed) { From 3b2ebd5d360fae5470122864798f9efefa1c0b37 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 2 Aug 2016 12:50:07 -0700 Subject: [PATCH 063/155] AP_BattMonitor: prevent voltage failsafe from triggering on extremely low voltages --- libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index 9f572e1fbf..21d78a54c2 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -195,7 +195,9 @@ void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_c } // check critical battery levels - if ((voltage_used > 0) && (_params._critical_voltage > 0) && (voltage_used < _params._critical_voltage)) { + if ((voltage_used > 0) && (_params._critical_voltage > 0) && + (voltage_used < _params._critical_voltage) && + (voltage_used > _params._critical_voltage*0.25)) { critical_voltage = true; } else { critical_voltage = false; @@ -209,7 +211,9 @@ void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_c critical_capacity = false; } - if ((voltage_used > 0) && (_params._low_voltage > 0) && (voltage_used < _params._low_voltage)) { + if ((voltage_used > 0) && (_params._low_voltage > 0) && + (voltage_used < _params._low_voltage) && + (voltage_used > _params._low_voltage*0.25)) { low_voltage = true; } else { low_voltage = false; From 15e879e22fd719b4fe2deb414ece5bc519dd5c2c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 21 Jul 2019 19:42:42 +1000 Subject: [PATCH 064/155] AP_BattMonitor: added LandIfManual battery failsafe option --- libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index a2384f4381..11ce3d7b69 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -128,7 +128,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @DisplayName: Low battery failsafe action // @Description: What action the vehicle should perform if it hits a low battery failsafe // @Values{Plane}: 0:None,1:RTL,2:Land,3:Terminate,4:QLand - // @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate + // @Values{Copter}: 0:None,1:Land,2:RTL,3:SmartRTL or RTL,4:SmartRTL or Land,5:Terminate,6:LandIfManual // @Values{Sub}: 0:None,2:Disarm,3:Enter surface mode // @Values{Rover}: 0:None,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold,5:Terminate // @Values{Tracker}: 0:None From 14ae3611ae7823d422a1c30243f77d1ed7385ed4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Sep 2019 10:54:06 +1000 Subject: [PATCH 065/155] AP_BattMonitor: added battery monitor backend based on SoC table this uses BATT_MONITOR=20 to select a table based battery monitor where the table is used when disarmed and the integration of current when armed The table is specific to a particular battery type --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 5 + libraries/AP_BattMonitor/AP_BattMonitor.h | 2 + .../AP_BattMonitor/AP_BattMonitor_Analog.h | 4 +- .../AP_BattMonitor_Analog_Table.cpp | 105 ++++++++++++++++++ .../AP_BattMonitor_Analog_Table.h | 25 +++++ .../AP_BattMonitor/AP_BattMonitor_Params.h | 1 + 6 files changed, 140 insertions(+), 2 deletions(-) create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.cpp create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.h diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 284c56b72f..3d33b9a1ff 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -1,5 +1,6 @@ #include "AP_BattMonitor.h" #include "AP_BattMonitor_Analog.h" +#include "AP_BattMonitor_Analog_Table.h" #include "AP_BattMonitor_SMBus.h" #include "AP_BattMonitor_Bebop.h" #include "AP_BattMonitor_BLHeliESC.h" @@ -112,6 +113,10 @@ AP_BattMonitor::init() case AP_BattMonitor_Params::BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT: drivers[instance] = new AP_BattMonitor_Analog(*this, state[instance], _params[instance]); break; + case AP_BattMonitor_Params::BattMonitor_TYPE_ANALOG_TABLE: + drivers[instance] = new AP_BattMonitor_Analog_Table(*this, state[instance], _params[instance]); + _num_instances++; + break; case AP_BattMonitor_Params::BattMonitor_TYPE_SOLO: drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance], hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_INTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR, diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index af285ac1d2..a88dd61fd4 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -22,6 +22,7 @@ // declare backend class class AP_BattMonitor_Backend; class AP_BattMonitor_Analog; +class AP_BattMonitor_Analog_Table; class AP_BattMonitor_SMBus; class AP_BattMonitor_SMBus_Solo; class AP_BattMonitor_SMBus_Maxell; @@ -31,6 +32,7 @@ class AP_BattMonitor { friend class AP_BattMonitor_Backend; friend class AP_BattMonitor_Analog; + friend class AP_BattMonitor_Analog_Table; friend class AP_BattMonitor_SMBus; friend class AP_BattMonitor_SMBus_Solo; friend class AP_BattMonitor_SMBus_Maxell; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h index a34a736345..8978407edd 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h @@ -83,13 +83,13 @@ class AP_BattMonitor_Analog : public AP_BattMonitor_Backend AP_BattMonitor_Analog(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms); /// Read the battery voltage and current. Should be called at 10hz - void read() override; + virtual void read() override; /// returns true if battery monitor provides consumed energy info bool has_consumed_energy() const override { return has_current(); } /// returns true if battery monitor provides current info - bool has_current() const override; + virtual bool has_current() const override; void init(void) override {} diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.cpp new file mode 100644 index 0000000000..a49252fada --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.cpp @@ -0,0 +1,105 @@ +#include +#include "AP_BattMonitor_Analog_Table.h" + +extern const AP_HAL::HAL& hal; + +// assume 12 cells +#define TABLE_NUM_CELLS 12 + +/* + state of charge table for a battery. This should be chosen based on + a battery that is at maximum age of batteries that will be used in + the vehicle + */ +static const struct { + float volt_per_cell; + float soc_pct; +} soc_table[] = { + { 4.173, 100 }, + { 4.112, 96.15 }, + { 4.085, 92.31 }, + { 4.071, 88.46 }, + { 4.039, 84.62 }, + { 3.987, 80.77 }, + { 3.943, 76.92 }, + { 3.908, 73.08 }, + { 3.887, 69.23 }, + { 3.854, 65.38 }, + { 3.833, 61.54 }, + { 3.801, 57.69 }, + { 3.783, 53.85 }, + { 3.742, 50 }, + { 3.715, 46.15 }, + { 3.679, 42.31 }, + { 3.636, 38.46 }, + { 3.588, 34.62 }, + { 3.543, 30.77 }, + { 3.503, 26.92 }, + { 3.462, 23.08 }, + { 3.379, 19.23 }, + { 3.296, 15.38 }, + { 3.218, 11.54 }, + { 3.165, 7.69 }, + { 3.091, 3.85 }, + { 2.977, 0 }}; + +/* + lookup SoC in table, returning SoC as a percentage + */ +float AP_BattMonitor_Analog_Table::lookup_SoC_table(float voltage) +{ + float per_cell = voltage / TABLE_NUM_CELLS; + + if (per_cell >= soc_table[0].volt_per_cell) { + return 100.0; + } + + for (uint8_t i=1; i= soc_table[i].volt_per_cell) { + // linear interpolation between table rows + float dv1 = per_cell - soc_table[i].volt_per_cell; + float dv2 = soc_table[i-1].volt_per_cell - soc_table[i].volt_per_cell; + float soc1 = soc_table[i].soc_pct; + float soc2 = soc_table[i-1].soc_pct; + return soc1 + (dv1 / dv2) * (soc2 - soc1); + } + } + // off the bottom of the table + return 0; +} + +/* + read - read the voltage and current + Use SoC table when disarmed +*/ +void AP_BattMonitor_Analog_Table::read() +{ + // first call base class read() method + AP_BattMonitor_Analog::read(); + + uint32_t now = AP_HAL::millis(); + bool armed = hal.util->get_soft_armed(); + if (armed) { + last_armed_ms = now; + using_table = false; + } + + // if we have been disarmed for more than 2 minutes then we start using the table + if (now - last_armed_ms > 120000) { + using_table = true; + } + + if (!armed && _state.voltage < 2.0*TABLE_NUM_CELLS) { + // below 2.0v/cell we assume battery is removed, force use of + // table when new battery is inserted. The threshold is chosen + // to make it more likely that a floating voltage pin will + // detect a low enough voltage to trigger table use + using_table = true; + } + + if (using_table) { + // reset remaining capacity based on the table + float soc_pct = lookup_SoC_table(_state.voltage); + reset_remaining(soc_pct); + } +} diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.h b/libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.h new file mode 100644 index 0000000000..9a344b2c25 --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog_Table.h @@ -0,0 +1,25 @@ +#pragma once + +#include "AP_BattMonitor_Analog.h" + +class AP_BattMonitor_Analog_Table : public AP_BattMonitor_Analog +{ +public: + /// Constructor + AP_BattMonitor_Analog_Table(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params ¶ms) : + AP_BattMonitor_Analog(mon, mon_state, params) {} + + + /// Read the battery voltage and current. Should be called at 10hz + void read() override; + + /// returns true if battery monitor provides current info + bool has_current() const override { return true; } + +private: + uint32_t last_armed_ms; + bool using_table = true; + + // lookup SoC in table, returning SoC as a percentage + float lookup_SoC_table(float voltage); +}; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 072ecfca7c..009843e24e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -25,6 +25,7 @@ class AP_BattMonitor_Params { BattMonitor_TYPE_Sum = 10, BattMonitor_TYPE_FuelFlow = 11, BattMonitor_TYPE_FuelLevel_PWM = 12, + BattMonitor_TYPE_ANALOG_TABLE = 20, }; // low voltage sources (used for BATT_LOW_TYPE parameter) From 69c4b5429dc24d99d3fdd8515b2967c9a9886c44 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 28 Jul 2016 14:25:07 -0700 Subject: [PATCH 066/155] AP_NavEKF2: change priority of statustext messages --- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 2 +- libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index 039b1036c3..71cccb3928 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -266,7 +266,7 @@ void NavEKF2_core::setAidingMode() switch (PV_AidingMode) { case AID_NONE: // We have ceased aiding - gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u has stopped aiding",(unsigned)imu_index); + gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u has stopped aiding",(unsigned)imu_index); // When not aiding, estimate orientation & height fusing synthetic constant position and zero velocity measurement to constrain tilt errors posTimeout = true; velTimeout = true; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp index fed0a152cc..37fe114a5d 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp @@ -149,7 +149,7 @@ void NavEKF2_core::controlMagYawReset() if (finalResetRequest) { gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u in-flight yaw alignment complete",(unsigned)imu_index); } else if (interimResetRequest) { - gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index); + gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index); } // update the yaw reset completed status From 99a3f6d2ac6b92fca39842f5465843578fa9f888 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 9 Feb 2017 12:08:19 -0800 Subject: [PATCH 067/155] AP_NavEKF2: increase baro floor limit to 8 --- libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp index 61d947f4f2..ae537f89be 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp @@ -672,7 +672,7 @@ void NavEKF2_core::FuseVelPosNED() R_OBS[obsIndex] *= sq(gpsNoiseScaler); } else if (obsIndex == 5) { innovVelPos[obsIndex] = stateStruct.position[obsIndex-3] - velPosObs[obsIndex]; - const float gndMaxBaroErr = 4.0f; + const float gndMaxBaroErr = 8.0f; const float gndBaroInnovFloor = -0.5f; if(getTouchdownExpected() && activeHgtSource == HGT_SOURCE_BARO) { From 1c47d83004d16019e6f65416c4c3d04e2eab60c5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 29 Jul 2019 12:15:33 +1000 Subject: [PATCH 068/155] AP_NavEKF2: use max of all lanes for EKF_STATUS_REPORT this allows an existing MAVLink GCS to detect if one of the EKF lanes is performing badly --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 63 ++++++++++++++++++++- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 56 ------------------ libraries/AP_NavEKF2/AP_NavEKF2_core.h | 5 +- 3 files changed, 63 insertions(+), 61 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 12a0d75f5a..8e70e41a25 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1347,11 +1347,70 @@ void NavEKF2::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const } // send an EKF_STATUS_REPORT message to GCS +// for each variance we send the maximum of all lanes void NavEKF2::send_status_report(mavlink_channel_t chan) { - if (core) { - core[primary].send_status_report(chan); + if (!core) { + return; + } + nav_filter_status filterStatus = core[primary].filterStatus; + + // prepare flags + uint16_t flags = 0; + if (filterStatus.flags.attitude) { + flags |= EKF_ATTITUDE; + } + if (filterStatus.flags.horiz_vel) { + flags |= EKF_VELOCITY_HORIZ; + } + if (filterStatus.flags.vert_vel) { + flags |= EKF_VELOCITY_VERT; + } + if (filterStatus.flags.horiz_pos_rel) { + flags |= EKF_POS_HORIZ_REL; + } + if (filterStatus.flags.horiz_pos_abs) { + flags |= EKF_POS_HORIZ_ABS; + } + if (filterStatus.flags.vert_pos) { + flags |= EKF_POS_VERT_ABS; } + if (filterStatus.flags.terrain_alt) { + flags |= EKF_POS_VERT_AGL; + } + if (filterStatus.flags.const_pos_mode) { + flags |= EKF_CONST_POS_MODE; + } + if (filterStatus.flags.pred_horiz_pos_rel) { + flags |= EKF_PRED_POS_HORIZ_REL; + } + if (filterStatus.flags.pred_horiz_pos_abs) { + flags |= EKF_PRED_POS_HORIZ_ABS; + } + + // get variances + float velVar=0, posVar=0, hgtVar=0, tasVar=0, magVarLen=0, rngVar=0; + Vector2f offset; + + for (uint8_t i=0; i 0) || core[i].PV_AidingMode == NavEKF2_core::AID_RELATIVE || core[i].flowDataValid) { + rngVar = MAX(rngVar, sqrtf(core[primary].auxRngTestRatio)); + } + } + + // send message + mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVarLen, rngVar, tasVar); } // provides the height limit to be observed by the control loops diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index ccb958b05b..5db4e32f9f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -536,62 +536,6 @@ void NavEKF2_core::getFilterGpsStatus(nav_gps_status &faults) const faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static) } -// send an EKF_STATUS message to GCS -void NavEKF2_core::send_status_report(mavlink_channel_t chan) -{ - // prepare flags - uint16_t flags = 0; - if (filterStatus.flags.attitude) { - flags |= EKF_ATTITUDE; - } - if (filterStatus.flags.horiz_vel) { - flags |= EKF_VELOCITY_HORIZ; - } - if (filterStatus.flags.vert_vel) { - flags |= EKF_VELOCITY_VERT; - } - if (filterStatus.flags.horiz_pos_rel) { - flags |= EKF_POS_HORIZ_REL; - } - if (filterStatus.flags.horiz_pos_abs) { - flags |= EKF_POS_HORIZ_ABS; - } - if (filterStatus.flags.vert_pos) { - flags |= EKF_POS_VERT_ABS; - } - if (filterStatus.flags.terrain_alt) { - flags |= EKF_POS_VERT_AGL; - } - if (filterStatus.flags.const_pos_mode) { - flags |= EKF_CONST_POS_MODE; - } - if (filterStatus.flags.pred_horiz_pos_rel) { - flags |= EKF_PRED_POS_HORIZ_REL; - } - if (filterStatus.flags.pred_horiz_pos_abs) { - flags |= EKF_PRED_POS_HORIZ_ABS; - } - - // get variances - float velVar, posVar, hgtVar, tasVar; - Vector3f magVar; - Vector2f offset; - getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); - - // Only report range finder normalised innovation levels if the EKF needs the data for primary - // height estimation or optical flow operation. This prevents false alarms at the GCS if a - // range finder is fitted for other applications - float temp; - if (((frontend->_useRngSwHgt > 0) && activeHgtSource == HGT_SOURCE_RNG) || (PV_AidingMode == AID_RELATIVE && flowDataValid)) { - temp = sqrtf(auxRngTestRatio); - } else { - temp = 0.0f; - } - - // send message - mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp, tasVar); -} - // report the reason for why the backend is refusing to initialise const char *NavEKF2_core::prearm_failure_reason(void) const { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index 1ce57d38dc..c7fadc22c9 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -62,6 +62,8 @@ class AP_AHRS; class NavEKF2_core : public NavEKF_core_common { public: + friend class NavEKF2; + // Constructor NavEKF2_core(NavEKF2 *_frontend); @@ -270,9 +272,6 @@ class NavEKF2_core : public NavEKF_core_common */ void getFilterStatus(nav_filter_status &status) const; - // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan); - // provides the height limit to be observed by the control loops // returns false if no height limiting is required // this is needed to ensure the vehicle does not fly too high when using optical flow navigation From 124c50afc36a5cda6f2b04ee1b6d0a84dd3bdec6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 29 Jul 2019 12:15:33 +1000 Subject: [PATCH 069/155] AP_NavEKF3: use max of all lanes for EKF_STATUS_REPORT this allows an existing MAVLink GCS to detect if one of the EKF lanes is performing badly --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 66 ++++++++++++++++++++- libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp | 60 ------------------- libraries/AP_NavEKF3/AP_NavEKF3_core.h | 5 +- 3 files changed, 66 insertions(+), 65 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 4c1acc7a4f..40c433b1d1 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1441,11 +1441,73 @@ void NavEKF3::getFilterGpsStatus(int8_t instance, nav_gps_status &status) const } // send an EKF_STATUS_REPORT message to GCS +// for each variance we send the maximum of all lanes void NavEKF3::send_status_report(mavlink_channel_t chan) { - if (core) { - core[primary].send_status_report(chan); + if (!core) { + return; + } + nav_filter_status filterStatus = core[primary].filterStatus; + + // prepare flags + uint16_t flags = 0; + if (filterStatus.flags.attitude) { + flags |= EKF_ATTITUDE; + } + if (filterStatus.flags.horiz_vel) { + flags |= EKF_VELOCITY_HORIZ; + } + if (filterStatus.flags.vert_vel) { + flags |= EKF_VELOCITY_VERT; + } + if (filterStatus.flags.horiz_pos_rel) { + flags |= EKF_POS_HORIZ_REL; + } + if (filterStatus.flags.horiz_pos_abs) { + flags |= EKF_POS_HORIZ_ABS; + } + if (filterStatus.flags.vert_pos) { + flags |= EKF_POS_VERT_ABS; + } + if (filterStatus.flags.terrain_alt) { + flags |= EKF_POS_VERT_AGL; } + if (filterStatus.flags.const_pos_mode) { + flags |= EKF_CONST_POS_MODE; + } + if (filterStatus.flags.pred_horiz_pos_rel) { + flags |= EKF_PRED_POS_HORIZ_REL; + } + if (filterStatus.flags.pred_horiz_pos_abs) { + flags |= EKF_PRED_POS_HORIZ_ABS; + } + if (filterStatus.flags.gps_glitching) { + flags |= (1<<15); + } + + // get variances + float velVar=0, posVar=0, hgtVar=0, tasVar=0, magVarLen=0, rngVar=0; + Vector2f offset; + + for (uint8_t i=0; i 0) || core[i].PV_AidingMode == NavEKF3_core::AID_RELATIVE || core[i].flowDataValid) { + rngVar = MAX(rngVar, sqrtf(core[primary].auxRngTestRatio)); + } + } + + // send message + mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVarLen, rngVar, tasVar); } // provides the height limit to be observed by the control loops diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index ed18c8bba4..006a5798da 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -544,66 +544,6 @@ void NavEKF3_core::getFilterGpsStatus(nav_gps_status &faults) const faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static) } -// send an EKF_STATUS message to GCS -void NavEKF3_core::send_status_report(mavlink_channel_t chan) -{ - // prepare flags - uint16_t flags = 0; - if (filterStatus.flags.attitude) { - flags |= EKF_ATTITUDE; - } - if (filterStatus.flags.horiz_vel) { - flags |= EKF_VELOCITY_HORIZ; - } - if (filterStatus.flags.vert_vel) { - flags |= EKF_VELOCITY_VERT; - } - if (filterStatus.flags.horiz_pos_rel) { - flags |= EKF_POS_HORIZ_REL; - } - if (filterStatus.flags.horiz_pos_abs) { - flags |= EKF_POS_HORIZ_ABS; - } - if (filterStatus.flags.vert_pos) { - flags |= EKF_POS_VERT_ABS; - } - if (filterStatus.flags.terrain_alt) { - flags |= EKF_POS_VERT_AGL; - } - if (filterStatus.flags.const_pos_mode) { - flags |= EKF_CONST_POS_MODE; - } - if (filterStatus.flags.pred_horiz_pos_rel) { - flags |= EKF_PRED_POS_HORIZ_REL; - } - if (filterStatus.flags.pred_horiz_pos_abs) { - flags |= EKF_PRED_POS_HORIZ_ABS; - } - if (filterStatus.flags.gps_glitching) { - flags |= (1<<15); - } - - // get variances - float velVar, posVar, hgtVar, tasVar; - Vector3f magVar; - Vector2f offset; - getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); - - // Only report range finder normalised innovation levels if the EKF needs the data for primary - // height estimation or optical flow operation. This prevents false alarms at the GCS if a - // range finder is fitted for other applications - float temp; - if (((frontend->_useRngSwHgt > 0) && activeHgtSource == HGT_SOURCE_RNG) || (PV_AidingMode == AID_RELATIVE && flowDataValid)) { - temp = sqrtf(auxRngTestRatio); - } else { - temp = 0.0f; - } - - // send message - mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp, tasVar); - -} - // report the reason for why the backend is refusing to initialise const char *NavEKF3_core::prearm_failure_reason(void) const { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 0a09d8f55d..b7681fd77a 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -67,6 +67,8 @@ class AP_AHRS; class NavEKF3_core : public NavEKF_core_common { public: + friend class NavEKF3; + // Constructor NavEKF3_core(NavEKF3 *_frontend); @@ -326,9 +328,6 @@ class NavEKF3_core : public NavEKF_core_common */ void getFilterStatus(nav_filter_status &status) const; - // send an EKF_STATUS_REPORT message to GCS - void send_status_report(mavlink_channel_t chan); - // provides the height limit to be observed by the control loops // returns false if no height limiting is required // this is needed to ensure the vehicle does not fly too high when using optical flow navigation From 7e3097e65316d68ff1518f2b23677837dcf39869 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 14 Aug 2019 14:57:13 +1000 Subject: [PATCH 070/155] AP_NavEKF2: added EK2_MAG_LRN_LIM This sets a limit on EKF2 magnetometer offset learning --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 8 ++++++++ libraries/AP_NavEKF2/AP_NavEKF2.h | 2 ++ libraries/AP_NavEKF2/AP_NavEKF2_core.cpp | 13 +++++++++++++ libraries/AP_NavEKF2/AP_NavEKF2_core.h | 3 +++ 4 files changed, 26 insertions(+) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 8e70e41a25..804e65ab22 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -582,6 +582,14 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @RebootRequired: False AP_GROUPINFO("HRT_FILT", 53, NavEKF2, _hrt_filt_freq, 2.0f), + // @Param: MAG_LRN_LIM + // @DisplayName: Magnetometer offset learning limit + // @Description: This limits the size of the learned magnetometer offsets. A value of zero means no limit. Limiting the learned offsets can be helpful when the compass calibration is known to be good and the vehicle is operating in an environment that can lead to significant incorrect learned offsets due to temporary local fields + // @User: Advanced + // @Range: 0 500 + // @Units: mGauss + AP_GROUPINFO("MAG_LRN_LIM", 54, NavEKF2, _mag_learn_limit, 0), + AP_GROUPEND }; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index b0d4bc39ef..a993c6ebfd 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -418,12 +418,14 @@ class NavEKF2 { AP_Int8 _flowUse; // Controls if the optical flow data is fused into the main navigation estimator and/or the terrain estimator. AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field. AP_Float _hrt_filt_freq; // frequency of output observer height rate complementary filter in Hz + AP_Int16 _mag_learn_limit; // limit on learned magnetometer offsets // Possible values for _flowUse #define FLOW_USE_NONE 0 #define FLOW_USE_NAV 1 #define FLOW_USE_TERRAIN 2 + // Tuning parameters const float gpsNEVelVarAccScale = 0.05f; // Scale factor applied to NE velocity measurement variance due to manoeuvre acceleration const float gpsDVelVarAccScale = 0.07f; // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 361ff83362..11b8c051ee 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -1523,6 +1523,17 @@ void NavEKF2_core::MagTableConstrain(void) table_earth_field_ga.z+limit_ga); } +// constrain states using limit on mag offsets +void NavEKF2_core::MagOffsetConstrain(void) +{ + if (frontend->_mag_learn_limit > 0) { + float limit_ga = frontend->_mag_learn_limit * 0.001f; + stateStruct.body_magfield.x = constrain_float(stateStruct.body_magfield.x, -limit_ga, limit_ga); + stateStruct.body_magfield.y = constrain_float(stateStruct.body_magfield.y, -limit_ga, limit_ga); + stateStruct.body_magfield.z = constrain_float(stateStruct.body_magfield.z, -limit_ga, limit_ga); + } +} + // constrain states to prevent ill-conditioning void NavEKF2_core::ConstrainStates() { @@ -1550,6 +1561,8 @@ void NavEKF2_core::ConstrainStates() MagTableConstrain(); } + MagOffsetConstrain(); + // body magnetic field limit for (uint8_t i=19; i<=21; i++) statesArray[i] = constrain_float(statesArray[i],-0.5f,0.5f); // wind velocity limit 100 m/s (could be based on some multiple of max airspeed * EAS2TAS) - TODO apply circular limit diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index c7fadc22c9..be95981871 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -511,6 +511,9 @@ class NavEKF2_core : public NavEKF_core_common // constrain earth field using WMM tables void MagTableConstrain(void); + // constrain mag offsets + void MagOffsetConstrain(void); + // fuse selected position, velocity and height measurements void FuseVelPosNED(); From f3191a26cd60143d789ca5dab19329630f35fa0c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 21 Jun 2019 09:03:30 +1000 Subject: [PATCH 071/155] HAL_ChibiOS: added MttrCubeBlack build --- .../hwdef/MttrCubeBlack/defaults.parm | 250 ++++++++++++++++++ .../hwdef/MttrCubeBlack/hwdef.dat | 9 + 2 files changed, 259 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm new file mode 100644 index 0000000000..8573b0db4b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -0,0 +1,250 @@ +AHRS_EKF_TYPE 2 +AHRS_ORIENTATION 2 +AHRS_TRIM_X 0 +AHRS_TRIM_Y -0.0135 +ANGLE_MAX 2000 +ARMING_CHECK 16318 +ATC_ACCEL_P_MAX 36000 +ATC_ACCEL_R_MAX 36000 +ATC_ACCEL_Y_MAX 10000 +ATC_ANG_LIM_TC 3 +ATC_ANG_PIT_P 6 +ATC_ANG_RLL_P 6 +ATC_ANG_YAW_P 5 +ATC_RAT_PIT_D 0.012 +ATC_RAT_PIT_FILT 6 +ATC_RAT_PIT_IMAX 0.444 +ATC_RAT_PIT_P 0.055 +ATC_RAT_RLL_D 0.012 +ATC_RAT_RLL_FILT 6 +ATC_RAT_RLL_I 0.1 +ATC_RAT_RLL_IMAX 0.444 +ATC_RAT_RLL_P 0.055 +ATC_RAT_YAW_D 0 +ATC_RAT_YAW_FILT 1.617667 +ATC_RAT_YAW_I 0.088756 +ATC_RAT_YAW_IMAX 0.222 +ATC_RAT_YAW_P 0.4435 +ATC_SLEW_YAW 1500 +ATC_THR_MIX_MAX 0.5 +ATC_THR_MIX_MIN 0.1 +BATT_CAPACITY 15000 +BATT_MONITOR 4 +BATT_VOLT_MULT 22.7 +BRD_SAFETYENABLE 0 +BRD_SAFETY_MASK 0 +BRD_SER1_RTSCTS 2 +BRD_SER2_RTSCTS 2 +CAN_D1_UC_ESC_BM 0 +CAN_D1_UC_SRV_BM 0 +CAN_P1_BITRATE 1000000 +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 0 +CH7_OPT 0 +CHUTE_ALT_MIN 0 +CHUTE_DELAY_MS 500 +CHUTE_ENABLED 1 +CHUTE_TYPE 11 +COMPASS_DEV_ID 592905 +COMPASS_LEARN 2 +COMPASS_MOTCT 2 +COMPASS_MOT_X 2.38 +COMPASS_MOT_Y -0.67 +COMPASS_MOT_Z 1.93 +COMPASS_USE 1 +COMPASS_USE2 1 +COMPASS_USE3 0 +DISARM_DELAY 20 +EK2_ALT_M_NSE 3 +EK2_CHECK_SCALE 100 +EK2_ENABLE 1 +EK2_GBIAS_P_NSE 0.0004 +EK2_GPS_CHECK -1 +EK2_IMU_MASK 3 +EK2_MAGB_P_NSE 0.0001 +EK2_MAGE_P_NSE 0.001 +EK2_MAG_CAL 3 +EK2_RNG_USE_HGT -1 +FENCE_ENABLE 0 +FLTMODE1 0 +FLTMODE2 0 +FLTMODE3 0 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 9 +FRAME_CLASS 1 +FRAME_TYPE 1 +FS_GCS_ENABLE 0 +FS_THR_ENABLE 6 +FS_THR_VALUE 0 +GND_EFFECT_COMP 1 +GPS_HDOP_GOOD 175 +GPS_POS1_X 0.182 +GPS_POS1_Y -0.05 +GPS_POS1_Z -0.04 +GPS_SAVE_CFG 2 +GPS_TYPE 2 +INS_ACCEL_FILTER 20 +INS_FAST_SAMPLE 5 +INS_GYRO_FILTER 20 +INS_GYR_CAL 0 +INS_POS1_X -0.077 +INS_POS1_Y 0 +INS_POS1_Z -0.05 +INS_POS2_X -0.077 +INS_POS2_Y 0 +INS_POS2_Z -0.05 +INS_POS3_X -0.077 +INS_POS3_Y 0 +INS_POS3_Z -0.05 +INS_TRIM_OPTION 0 +INS_USE 1 +INS_USE2 1 +INS_USE3 1 +LAND_REPOSITION 0 +LAND_SPEED 50 +LAND_SPEED_HIGH 100 +LOG_DISARMED 0 +LOG_FILE_BUFSIZE 50 +LOG_REPLAY 0 +MIS_RESTART 0 +MOT_BAT_CURR_MAX 60 +MOT_BAT_CURR_TC 2 +MOT_BAT_POW_MAX 2000 +MOT_BAT_VOLT_MAX 50.8 +MOT_BAT_VOLT_MIN 35 +MOT_HOVER_LEARN 0 +MOT_PWM_MAX 1940 +MOT_PWM_MIN 1060 +MOT_SAFE_DISARM 0 +MOT_SPIN_ARM 0.11 +MOT_SPIN_MAX 1 +MOT_SPIN_MIN 0.15 +MOT_THST_EXPO 0.8 +PILOT_THR_BHV 0 +PILOT_TKOFF_ALT 150 +PLND_ACC_P_NSE 2 +PLND_CAM_POS_X 0.165 +PLND_CAM_POS_Y -0.014 +PLND_CAM_POS_Z 0.151 +PLND_ENABLED 1 +PLND_LAND_OFS_X 0 +PLND_LAND_OFS_Y -2.6 +PLND_TYPE 2 +PLND_YAW_ALIGN 18000 +PSC_ACC_XY_FILT 5 +RC1_DZ 30 +RC1_MAX 2000 +RC1_MIN 1002 +RC1_TRIM 1500 +RC2_DZ 30 +RC2_MAX 1999 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_DZ 30 +RC3_MAX 1998 +RC3_MIN 999 +RC3_TRIM 1500 +RC4_DZ 40 +RC4_MAX 1997 +RC4_MIN 1002 +RC4_TRIM 1500 +RCMAP_PITCH 2 +RCMAP_ROLL 1 +RCMAP_THROTTLE 3 +RCMAP_YAW 4 +RNGFND2_ADDR 112 +RNGFND2_MAX_CM 700 +RNGFND2_MIN_CM 20 +RNGFND2_TYPE 0 +RNGFND_ADDR 102 +RNGFND_GNDCLEAR 15 +RNGFND_MAX_CM 12000 +RNGFND_MIN_CM 0 +RNGFND_POS_X -0.124 +RNGFND_POS_Y -0.097 +RNGFND_POS_Z 0.037 +RNGFND_SCALING 1 +RNGFND_STOP_PIN 55 +RNGFND_TYPE 0 +SERIAL0_BAUD 115 +SERIAL0_PROTOCOL 1 +SERIAL1_BAUD 921 +SERIAL1_PROTOCOL 1 +SERIAL2_BAUD 57 +SERIAL2_PROTOCOL 5 +SERIAL3_BAUD 38 +SERIAL3_PROTOCOL 5 +SERIAL4_BAUD 115 +SERIAL4_PROTOCOL 100 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL -1 +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 34 +SERVO3_FUNCTION 36 +SERVO4_FUNCTION 35 +SYSID_MYGCS 255 +TERRAIN_ENABLE 0 +WPNAV_ACCEL 150 +WPNAV_ACCEL_Z 100 +WPNAV_RADIUS 200 +WPNAV_SPEED 1600 +WPNAV_SPEED_DN 400 +WPNAV_SPEED_UP 400 +COMPASS_ORIENT 35 +MOT_THST_HOVER 0.185 +ATC_RAT_PIT_I 0.1 +FS_EKF_ACTION 4 +COMPASS_PRIMARY 1 +FS_EKF_THRESH 0.8 +COMPASS_DEV_ID2 73475 +COMPASS_MOT2_X 1.87 +COMPASS_MOT2_Y 0.45 +COMPASS_MOT2_Z -1.05 +COMPASS_ORIENT2 36 +COMPASS_TYPEMASK -2113 +EK2_ALT_SOURCE 2 +GPS_AUTO_SWITCH 1 +GPS_POS2_X 0.182 +GPS_POS2_Y 0.05 +GPS_POS2_Z -0.04 +GPS_TYPE2 2 +INS_LOG_BAT_MASK 5 +BATT_AMP_PERVLT 45 +BATT_LOW_VOLT 36 +BATT_FS_LOW_ACT 0 +BATT_LOW_MAH 0 +LOIT_ANG_MAX 20 +PSC_ACCZ_D 0 +PSC_ACCZ_FF 0 +PSC_ACCZ_FILT 20 +PSC_ACCZ_I 0.5 +PSC_ACCZ_IMAX 800 +PSC_ACCZ_P 0.25 +PSC_ANGLE_MAX 0 +PSC_POSXY_P 1.2 +PSC_POSZ_P 1 +PSC_VELXY_D 0.35 +PSC_VELXY_D_FILT 5 +PSC_VELXY_FILT 5 +PSC_VELXY_I 1.2 +PSC_VELXY_IMAX 1000 +PSC_VELXY_P 1.2 +PSC_VELZ_P 3.5 +BATT_CRT_VOLT 0 +PILOT_SPEED_UP 300 +ATC_INPUT_TC 0.0833 +LOIT_BRK_JERK 3400 +LOIT_ACC_MAX 350 +LOIT_SPEED 750 +BRD_SAFETYOPTION 0 +INS_LOG_BAT_OPT 1 +LOG_BITMASK 65535 +ARM_GPS_HACC 2 +ARM_GPS_VACC 2 +LOG_BACKEND_TYPE 1 +TOFF_ALT_CHANGE 2 +TOFF_BARO_DIP 2 +TOFF_HOV_PCT 80 +TOFF_POS_CHANGE 2 +WP_NAVALT_MAX 3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat new file mode 100644 index 0000000000..db5b2d6adb --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat @@ -0,0 +1,9 @@ +# hw definition for Matternet CubeBlack build + +include ../CubeBlack/hwdef.dat + +define MODE_SMARTRTL_ENABLED DISABLED +define SPRAYER_ENABLED DISABLED +define GRIPPER_ENABLED DISABLED +define WINCH_ENABLED DISABLED + From 85c3fcb3594e1b39bb9e4f64aefd59fdab01e3b7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 20 Aug 2019 07:55:21 +1000 Subject: [PATCH 072/155] HAL_ChibiOS: disable transmitter ESC cal in MttrCubeBlack --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index 8573b0db4b..2e3d416496 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -248,3 +248,4 @@ TOFF_BARO_DIP 2 TOFF_HOV_PCT 80 TOFF_POS_CHANGE 2 WP_NAVALT_MAX 3 +ESC_CALIBRATION 9 From b7d02077b8cb8498f54aca9d121ababf31fe162d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Sep 2019 10:55:36 +1000 Subject: [PATCH 073/155] HAL_ChibiOS: enable new table based battery SoC system --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index 2e3d416496..b040b5b30a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -28,8 +28,8 @@ ATC_RAT_YAW_P 0.4435 ATC_SLEW_YAW 1500 ATC_THR_MIX_MAX 0.5 ATC_THR_MIX_MIN 0.1 -BATT_CAPACITY 15000 -BATT_MONITOR 4 +BATT_CAPACITY 13000 +BATT_MONITOR 20 BATT_VOLT_MULT 22.7 BRD_SAFETYENABLE 0 BRD_SAFETY_MASK 0 From 212b5bf41cdaecb70e8c44c8b69a33c4dbd0fa8e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 2 Oct 2019 11:11:38 +1000 Subject: [PATCH 074/155] HAL_ChibiOS: default LOG_FILE_DSRMROT=1 for MatterNet --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index b040b5b30a..6c97992dbd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -106,6 +106,7 @@ LAND_SPEED 50 LAND_SPEED_HIGH 100 LOG_DISARMED 0 LOG_FILE_BUFSIZE 50 +LOG_FILE_DSRMROT 1 LOG_REPLAY 0 MIS_RESTART 0 MOT_BAT_CURR_MAX 60 From e985649982cbda9026835ca59fbc7ce7fc0bfab5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Oct 2019 13:56:17 +1000 Subject: [PATCH 075/155] HAL_ChibiOS: enable logging of ADSB vehicles --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index 6c97992dbd..061a4de66b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -250,3 +250,5 @@ TOFF_HOV_PCT 80 TOFF_POS_CHANGE 2 WP_NAVALT_MAX 3 ESC_CALIBRATION 9 +ADSB_ENABLE 1 +ADSB_LIST_RADIUS 10000 From 59d5eeda7c6c465f3308d55c532072e4437ddf5f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Oct 2019 15:12:45 +1000 Subject: [PATCH 076/155] HAL_ChibiOS: adjust defaults for CAN2 enable CAN2 (for CAN compass on 2nd bus) and lower logging buffer size a bit to give room for ADSB and CAN2 --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index 061a4de66b..e56e45c714 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -39,7 +39,9 @@ CAN_D1_UC_ESC_BM 0 CAN_D1_UC_SRV_BM 0 CAN_P1_BITRATE 1000000 CAN_P1_DRIVER 1 -CAN_P2_DRIVER 0 +CAN_P2_DRIVER 2 +CAN_D2_UC_ESC_BM 0 +CAN_D2_UC_SRV_BM 0 CH7_OPT 0 CHUTE_ALT_MIN 0 CHUTE_DELAY_MS 500 @@ -105,7 +107,7 @@ LAND_REPOSITION 0 LAND_SPEED 50 LAND_SPEED_HIGH 100 LOG_DISARMED 0 -LOG_FILE_BUFSIZE 50 +LOG_FILE_BUFSIZE 40 LOG_FILE_DSRMROT 1 LOG_REPLAY 0 MIS_RESTART 0 From 7895387691e319fc70a187ce67ae48ab9f28e051 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Oct 2019 15:19:03 +1000 Subject: [PATCH 077/155] HAL_ChibiOS: fixed default for COMPASS_TYPEMASK --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index e56e45c714..2b8634de7a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -205,7 +205,7 @@ COMPASS_MOT2_X 1.87 COMPASS_MOT2_Y 0.45 COMPASS_MOT2_Z -1.05 COMPASS_ORIENT2 36 -COMPASS_TYPEMASK -2113 +COMPASS_TYPEMASK 63423 EK2_ALT_SOURCE 2 GPS_AUTO_SWITCH 1 GPS_POS2_X 0.182 From 703ee030daa8d17e9a24b944f07e0557747d7c55 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 15:53:47 +1100 Subject: [PATCH 078/155] HAL_ChibiOS: raise ARMING_DELAY_SEC on MttrCubeBlack --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat index db5b2d6adb..a5f5b521d9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat @@ -7,3 +7,7 @@ define SPRAYER_ENABLED DISABLED define GRIPPER_ENABLED DISABLED define WINCH_ENABLED DISABLED +# increase arming delay +define ARMING_DELAY_SEC 3.0f + + From abd6010fd32ee219d15b2a6846e421a45fd35bcb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 16:40:09 +1100 Subject: [PATCH 079/155] HAL_ChibiOS: log for 60s after disarm for MttrCubeBlack --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat index a5f5b521d9..c4148a3445 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/hwdef.dat @@ -10,4 +10,5 @@ define WINCH_ENABLED DISABLED # increase arming delay define ARMING_DELAY_SEC 3.0f - +# log for 60s after disarm +define HAL_LOGGER_ARM_PERSIST 60 From b02c4f1e8ea6e00c64c90e7e7ca595aa87b9fe95 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 1 Aug 2016 16:20:32 -0700 Subject: [PATCH 080/155] Copter: disable surface tracking --- ArduCopter/Copter.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index fa41849be8..8fedd8617c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -306,7 +306,7 @@ class Copter : public AP_Vehicle { void set_surface(Surface new_surface); private: - Surface surface = Surface::GROUND; + Surface surface = Surface::NONE; float target_dist_cm; // desired distance in cm from ground or ceiling uint32_t last_update_ms; // system time of last update to target_alt_cm uint32_t last_glitch_cleared_ms; // system time of last handle glitch recovery From 99a36f67d8abb470a264a1f302a224249ab4d6f3 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 24 Jun 2016 15:38:23 -0700 Subject: [PATCH 081/155] Copter: send LANDING_TARGET message --- ArduCopter/GCS_Mavlink.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 0e1f3daa33..c6c8928cc0 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -265,6 +265,15 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) #endif break; + case MSG_LANDING_TARGET: +#if PRECISION_LANDING == ENABLED + CHECK_PAYLOAD_SIZE(LANDING_TARGET); + if (copter.precland.enabled()) { + copter.precland.send_landing_target(chan); + } +#endif + break; + case MSG_WIND: case MSG_SERVO_OUT: case MSG_AOA_SSA: @@ -451,6 +460,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_VIBRATION, MSG_RPM, MSG_ESC_TELEMETRY, + MSG_LANDING_TARGET, }; static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM From 730945f7a91176306ad587d141fc127cd831fe8d Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 17 Nov 2016 15:12:08 -0800 Subject: [PATCH 082/155] Copter: call parachute.init --- ArduCopter/system.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 811e1dba34..726e94914c 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -166,6 +166,10 @@ void Copter::init_ardupilot() camera_mount.init(); #endif +#if PARACHUTE == ENABLED + parachute.init(serial_manager); +#endif + #if PRECISION_LANDING == ENABLED // initialise precision landing init_precland(); From 8cb3439bf58d5ada728f74ca3909a58263f29b16 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 17 Nov 2016 15:15:36 -0800 Subject: [PATCH 083/155] Copter: eliminate minimum altitude for manual parachute release --- ArduCopter/crash_check.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 4fe7ad1c93..c5c2911f23 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -262,12 +262,14 @@ void Copter::parachute_manual_release() } // do not release if we are landed or below the minimum altitude above home +#if 0 if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) { // warn user of reason for failure gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low"); AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW); return; } +#endif // if we get this far release parachute parachute_release(); From 52d80593991c6a0951d413e6a40908144b2e4263 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 7 Dec 2016 12:16:46 -0800 Subject: [PATCH 084/155] Copter: add info messages to AUTO mode --- ArduCopter/mode_auto.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index d10c0106ec..e3b5f2fd04 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -533,6 +533,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) // exit_mission - function that is called once the mission completes void ModeAuto::exit_mission() { + gcs().send_text(MAV_SEVERITY_INFO,"Mission completed"); // play a tone AP_Notify::events.mission_complete = 1; // if we are not on the ground switch to loiter or land @@ -1167,6 +1168,7 @@ void ModeAuto::do_land(const AP_Mission::Mission_Command& cmd) if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) { // set state to fly to location land_state = LandStateType_FlyToLocation; + gcs().send_text(MAV_SEVERITY_INFO,"Flying to land location"); const Location target_loc = terrain_adjusted_location(cmd); @@ -1174,6 +1176,7 @@ void ModeAuto::do_land(const AP_Mission::Mission_Command& cmd) } else { // set landing state land_state = LandStateType_Descending; + gcs().send_text(MAV_SEVERITY_INFO,"Landing"); // initialise landing controller land_start(); @@ -1531,12 +1534,14 @@ bool ModeAuto::verify_land() // advance to next state land_state = LandStateType_Descending; + gcs().send_text(MAV_SEVERITY_INFO,"Landing"); } break; case LandStateType_Descending: // rely on THROTTLE_LAND mode to correctly update landing status retval = copter.ap.land_complete && (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE); + gcs().send_text(MAV_SEVERITY_INFO,"Landed"); break; default: From eb4ae5f716207e4f762f019b708481e67dabd941 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 30 Jan 2017 16:24:52 -0800 Subject: [PATCH 085/155] Copter: increase ARMING_DELAY_SEC to 3 to avoid failure to arm ESCs --- ArduCopter/APM_Config.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index c28a027b9b..b79b35b4f5 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -3,6 +3,8 @@ // If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer // valid! You should switch to using a HAL_BOARD flag in your local config.mk. +#define ARMING_DELAY_SEC 3.0f + // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) //#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space From 7469734d6e9751cb2f41d120860be092a6da4cd3 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 30 Jan 2017 16:25:52 -0800 Subject: [PATCH 086/155] Copter: don't set auto_armed on throttle up in auto mode --- ArduCopter/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 726e94914c..f4ef064739 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -425,7 +425,7 @@ void Copter::update_auto_armed() } // if motors are armed and throttle is above zero auto_armed should be true // if motors are armed and we are in throw mode, then auto_armed should be true - } else if (motors->armed() && !ap.using_interlock) { + } else if (motors->armed() && !ap.using_interlock && control_mode != Mode::Number::AUTO) { if(!ap.throttle_zero || control_mode == Mode::Number::THROW) { set_auto_armed(true); } From 305879407993695c3b6d9a934b5bc7ffecc7cf87 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 14 Mar 2017 14:00:32 -0700 Subject: [PATCH 087/155] Copter: slow auto descent sets throttle mix to minimum --- ArduCopter/land_detector.cpp | 28 +++++++++++++++++++++++++--- 1 file changed, 25 insertions(+), 3 deletions(-) diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index d8ed9b1870..ebc05edcd2 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -159,6 +159,22 @@ void Copter::update_throttle_thr_mix() } else { // autopilot controlled throttle + float xy_des_speed_cms = 0.0f; + float xy_speed_cms = 0.0f; + float des_climb_rate_cms = pos_control->get_desired_velocity().z; + + if (pos_control->is_active_xy()) { + Vector3f vel_target = pos_control->get_vel_target(); + vel_target.z = 0.0f; + xy_des_speed_cms = vel_target.length(); + } + + if (position_ok() || optflow_position_ok()) { + Vector3f vel = inertial_nav.get_velocity(); + vel.z = 0.0f; + xy_speed_cms = vel.length(); + } + // check for aggressive flight requests - requested roll or pitch angle below 15 degrees const Vector3f angle_target = attitude_control->get_att_target_euler_cd(); bool large_angle_request = (norm(angle_target.x, angle_target.y) > LAND_CHECK_LARGE_ANGLE_CD); @@ -175,10 +191,16 @@ void Copter::update_throttle_thr_mix() // check for requested decent bool descent_not_demanded = pos_control->get_desired_velocity().z >= 0.0f; - if ( large_angle_request || large_angle_error || accel_moving || descent_not_demanded) { - attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio()); - } else { + bool xy_speed_low = (position_ok() || optflow_position_ok()) && xy_speed_cms <= 125.0f; + bool xy_speed_demand_low = pos_control->is_active_xy() && xy_des_speed_cms <= 125.0f; + bool slow_descent_demanded = pos_control->is_active_z() && des_climb_rate_cms < 0.0f && des_climb_rate_cms >= -100.0f; + + bool slow_auto_descent = xy_speed_demand_low && xy_speed_low && slow_descent_demanded; + + if ( slow_auto_descent || !(large_angle_request || large_angle_error || accel_moving || descent_not_demanded) ) { attitude_control->set_throttle_mix_min(); + } else { + attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio()); } } #endif From ea578f2ada7220e687c718f5bd3bc867ddfad651 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 24 Mar 2017 11:22:02 -0700 Subject: [PATCH 088/155] Copter: reduce deceleration to LAND_SPEED --- ArduCopter/mode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index a2a3da4b9c..0a5b096dde 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -545,7 +545,7 @@ void Mode::land_run_vertical_control(bool pause_descent) max_land_descent_velocity = MIN(max_land_descent_velocity, -abs(g.land_speed)); // Compute a vertical velocity demand such that the vehicle approaches g2.land_alt_low. Without the below constraint, this would cause the vehicle to hover at g2.land_alt_low. - cmb_rate = AC_AttitudeControl::sqrt_controller(MAX(g2.land_alt_low,100)-get_alt_above_ground_cm(), pos_control->get_pos_z_p().kP(), pos_control->get_max_accel_z(), G_Dt); + cmb_rate = AC_AttitudeControl::sqrt_controller(MAX(g2.land_alt_low,100)-get_alt_above_ground_cm(), pos_control->get_pos_z_p().kP(), pos_control->get_accel_z()*0.25, G_Dt); // 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)); From 048fcfbc4db5b542d72c37f23c47a7e1c4b7bc7c Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 7 Apr 2017 13:36:45 -0700 Subject: [PATCH 089/155] Copter: set RANGEFINDER_WPNAV_FILT_HZ to 3 --- ArduCopter/APM_Config.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index b79b35b4f5..74351f33e9 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -5,6 +5,8 @@ #define ARMING_DELAY_SEC 3.0f +#define RANGEFINDER_WPNAV_FILT_HZ 3.0f + // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) //#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space From 970660ac8fe69d3af9ed8c4e3e53eb9e536af8ca Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 19 Apr 2017 22:11:35 -0700 Subject: [PATCH 090/155] Copter: move update_precland into fast_loop --- ArduCopter/Copter.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 6d8dd0032f..0f246a5968 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -130,9 +130,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if AC_FENCE == ENABLED SCHED_TASK_CLASS(AC_Fence, &copter.fence, update, 10, 100), #endif -#if PRECISION_LANDING == ENABLED - SCHED_TASK(update_precland, 400, 50), -#endif #if FRAME_CONFIG == HELI_FRAME SCHED_TASK(check_dynamic_flight, 50, 75), #endif @@ -248,6 +245,10 @@ void Copter::fast_loop() // -------------------- read_AHRS(); +#if PRECISION_LANDING == ENABLED + update_precland(); +#endif + #if FRAME_CONFIG == HELI_FRAME update_heli_control_dynamics(); #if MODE_AUTOROTATE_ENABLED == ENABLED From 2b04cb7827b61c7db649568d72339da3f067426c Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 10 May 2017 14:35:47 -0700 Subject: [PATCH 091/155] Copter: don't set auto_armed on throttle up in GUIDED mode --- ArduCopter/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index f4ef064739..f5152e505a 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -425,7 +425,7 @@ void Copter::update_auto_armed() } // if motors are armed and throttle is above zero auto_armed should be true // if motors are armed and we are in throw mode, then auto_armed should be true - } else if (motors->armed() && !ap.using_interlock && control_mode != Mode::Number::AUTO) { + } else if (motors->armed() && !ap.using_interlock && control_mode != Mode::Number::AUTO && control_mode != Mode::Number::GUIDED) { if(!ap.throttle_zero || control_mode == Mode::Number::THROW) { set_auto_armed(true); } From 71fc215df5fc1f3ae28995f7921587b9b5579519 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 2 Feb 2017 12:15:14 -0800 Subject: [PATCH 092/155] Copter: re-work parachute deployment criteria The parachute will now deploy when any of the following conditions are met: - Attitude error is greater than PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG for PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT_SEC seconds - Attitude error is greater than PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG *AND* tilt angle is greater than ANGLE_MAX + PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG - Height control is active *AND* vertical velocity error is above PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS *AND* abs(vertical velocity) is above PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS *AND* all of these conditions are true for PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_TIMEOUT_SEC - Flight mode is STABILIZE *AND* throttle is zero *AND* downward velocity is greater than 5 m/s --- ArduCopter/Copter.h | 7 +++ ArduCopter/crash_check.cpp | 88 +++++++++++++++++++-------------- libraries/AP_Logger/AP_Logger.h | 7 ++- 3 files changed, 64 insertions(+), 38 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 8fedd8617c..af0efc650e 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -590,6 +590,13 @@ class Copter : public AP_Vehicle { int16_t hover_roll_trim_scalar_slew; #endif + struct { + bool angle_error_excessive; + bool vel_z_error_excessive; + uint32_t angle_error_excessive_begin_ms; + uint32_t vel_z_error_excessive_begin_ms; + } parachute_check_state; + // ground effect detector struct { bool takeoff_expected; diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index c5c2911f23..10111c2026 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -145,19 +145,23 @@ void Copter::thrust_loss_check() #if PARACHUTE == ENABLED // Code to detect a crash main ArduCopter code -#define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute -#define PARACHUTE_CHECK_ANGLE_DEVIATION_CD 3000 // 30 degrees off from target indicates a loss of control - -// parachute_check - disarms motors and triggers the parachute if serious loss of control has been detected -// vehicle is considered to have a "serious loss of control" by the vehicle being more than 30 degrees off from the target roll and pitch angles continuously for 1 second +#define PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG 30.0f +#define PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT_SEC 0.5f +#define PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS 3.0f +#define PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_TIMEOUT_SEC 0.5f + +// parachute_check - checks whether the parachute should be deployed. There are several criteria for parachute deployment. The parachute will deploy when: +// - Attitude error is greater than PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG for PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT_SEC seconds +// - Attitude error is greater than PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG *AND* tilt angle is greater than ANGLE_MAX + PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG +// - Height control is active *AND* vertical velocity error is above PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS *AND* abs(vertical velocity) is above PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS *AND* all of these conditions are true for PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_TIMEOUT_SEC +// - Flight mode is STABILIZE *AND* throttle is zero *AND* downward velocity is greater than 5 m/s // called at MAIN_LOOP_RATE + void Copter::parachute_check() { - static uint16_t control_loss_count; // number of iterations we have been out of control - static int32_t baro_alt_start; - - // exit immediately if parachute is not enabled + // Return immediately if parachute is not enabled if (!parachute.enabled()) { + parachute_check_state.angle_error_excessive = false; return; } @@ -184,45 +188,55 @@ void Copter::parachute_check() // ensure we are flying if (ap.land_complete) { control_loss_count = 0; + parachute_check_state.angle_error_excessive = false; return; } - // ensure the first control_loss event is from above the min altitude - if (control_loss_count == 0 && parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100)) { - return; - } - - // check for angle error over 30 degrees + // Retrieve useful values const float angle_error = attitude_control->get_att_error_angle_deg(); - if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) { - if (control_loss_count > 0) { - control_loss_count--; - } - return; + const float tilt_angle = acosf(ahrs.get_rotation_body_to_ned().c.z); + const float tilt_angle_limit = attitude_control->get_tilt_limit_rad() + radians(PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG); + const float vel_z = -inertial_nav.get_velocity_z()*0.01f; // Convert cm/s to m/s and convert NEU to NED + const float vel_z_error = -pos_control->get_vel_error_z()*0.01f; // Convert cm/s to m/s and convert NEU to NED + + // Start attitude error timer + bool new_angle_error_excessive = angle_error > PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG; + if (new_angle_error_excessive && !parachute_check_state.angle_error_excessive) { + parachute_check_state.angle_error_excessive_begin_ms = millis(); } + parachute_check_state.angle_error_excessive = new_angle_error_excessive; - // increment counter - if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) { - control_loss_count++; + // Start vertical velocity error timer + bool new_vel_z_error_excessive = pos_control->is_active_z() && fabsf(vel_z) > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS && fabsf(vel_z_error) > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS; + if (new_vel_z_error_excessive && !parachute_check_state.vel_z_error_excessive) { + parachute_check_state.vel_z_error_excessive_begin_ms = millis(); } + parachute_check_state.vel_z_error_excessive = new_vel_z_error_excessive; - // record baro alt if we have just started losing control - if (control_loss_count == 1) { - baro_alt_start = baro_alt; + // Check for criterion: "Attitude error is greater than PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG for PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT_SEC seconds" + bool angle_error_excessive_timeout = parachute_check_state.angle_error_excessive && (millis()-parachute_check_state.angle_error_excessive_begin_ms)*1e-3f > PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT_SEC; - // exit if baro altitude change indicates we are not falling - } else if (baro_alt >= baro_alt_start) { - control_loss_count = 0; - return; + // Check for criterion: "Attitude error is greater than PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG *AND* tilt angle is greater than ANGLE_MAX + PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG" + bool tilt_angle_excessive = parachute_check_state.angle_error_excessive && tilt_angle > tilt_angle_limit; - // To-Do: add check that the vehicle is actually falling + // Check for criterion: "Height control is active *AND* vertical velocity error is above PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS *AND* abs(vertical velocity) is above PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS *AND* all of these conditions are true for PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_TIMEOUT_SEC" + bool vel_z_error_excessive_timeout = parachute_check_state.vel_z_error_excessive && (millis()-parachute_check_state.vel_z_error_excessive_begin_ms)*1e-3f > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_TIMEOUT_SEC; - // check if loss of control for at least 1 second - } else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) { - // reset control loss counter - control_loss_count = 0; - AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL); - // release parachute + // Check for criterion: "Flight mode is STABILIZE *AND* throttle is zero *AND* downward velocity is greater than 5 m/s" + bool stabilize_throttle_cut = control_mode == STABILIZE && ap.throttle_zero && vel_z > 5.0f; + + // Deploy the parachute if a criterion is met + if (angle_error_excessive_timeout) { + Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_ANGLE_ERROR_EXCESSIVE_TIMEOUT); + parachute_release(); + } else if (tilt_angle_excessive) { + Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_TILT_ANGLE_EXCESSIVE); + parachute_release(); + } else if (vel_z_error_excessive_timeout) { + Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_VEL_Z_ERROR_EXCESSIVE_TIMEOUT); + parachute_release(); + } else if (stabilize_throttle_cut) { + Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_STABILIZE_THROTTLE_CUT); parachute_release(); } diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 603097f0ac..64861c9794 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -157,9 +157,14 @@ enum class LogErrorCode : uint8_t { FAILED_CIRCLE_INIT = 4, DEST_OUTSIDE_FENCE = 5, -// parachute failed to deploy because of low altitude or landed +// parachute reasons PARACHUTE_TOO_LOW = 2, PARACHUTE_LANDED = 3, + PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT = 5, + PARACHUTE_TILT_ANGLE_EXCESSIVE = 6, + PARACHUTE_VEL_Z_ERROR_EXCESSIVE_TIMEOUT = 7, + PARACHUTE_STABILIZE_THROTTLE_CUT = 8, + // EKF check definitions EKFCHECK_BAD_VARIANCE = 2, EKFCHECK_VARIANCE_CLEARED = 0, From f7b422f87dc3df1344424811a69b489ea8d13ecc Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 9 Feb 2017 12:07:25 -0800 Subject: [PATCH 093/155] Copter: add parachute deployment option to EKF failsafe --- ArduCopter/defines.h | 1 + ArduCopter/ekf_check.cpp | 6 ++++++ libraries/AP_Logger/AP_Logger.h | 1 + 3 files changed, 8 insertions(+) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 69341bc101..01ac290037 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -221,6 +221,7 @@ enum HarmonicNotchDynamicMode { #define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe #define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe #define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize +#define FS_EKF_ACTION_PARACHUTE 4 // for mavlink SET_POSITION_TARGET messages #define MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE ((1<<0) | (1<<1) | (1<<2)) diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index a69ae93b0a..59fa329350 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -162,6 +162,12 @@ void Copter::failsafe_ekf_event() set_mode_land_with_pause(ModeReason::EKF_FAILSAFE); } break; + + case FS_EKF_ACTION_PARACHUTE: + Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_EKF_FAILSAFE); + parachute_release(); + break; + case FS_EKF_ACTION_LAND: case FS_EKF_ACTION_LAND_EVEN_STABILIZE: default: diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 64861c9794..3e2741f81c 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -164,6 +164,7 @@ enum class LogErrorCode : uint8_t { PARACHUTE_TILT_ANGLE_EXCESSIVE = 6, PARACHUTE_VEL_Z_ERROR_EXCESSIVE_TIMEOUT = 7, PARACHUTE_STABILIZE_THROTTLE_CUT = 8, + PARACHUTE_REASON_EKF_FAILSAFE = 9, // EKF check definitions EKFCHECK_BAD_VARIANCE = 2, From 1d3e7a7e1da0632b57b2fd13c42b8c3aad7fd19e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 31 May 2017 15:53:14 -0700 Subject: [PATCH 094/155] Copter: disallow pilot yaw in AUTO mode --- ArduCopter/Attitude.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index 1ec6fd815e..568dc522c5 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -10,6 +10,10 @@ float Copter::get_pilot_desired_yaw_rate(int16_t stick_angle) } float yaw_request; + if (control_mode == Mode::Number::AUTO) { + return 0; + } + // calculate yaw rate request if (g2.acro_y_expo <= 0) { yaw_request = stick_angle * g.acro_yaw_p; From 04f85653b4d85a057398517a431ca0068ca6ca18 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 2 Jun 2017 14:41:40 -0700 Subject: [PATCH 095/155] Copter: disallow switch to guided mode when armed --- ArduCopter/mode_guided.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 1b5fc8a0c7..d6f93dba81 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -40,6 +40,10 @@ struct Guided_Limit { // guided_init - initialise guided controller bool ModeGuided::init(bool ignore_checks) { + if (motors->armed()) { + return false; + } + // start in position control mode pos_control_start(); return true; From 633e083f44ad5e1cc3db6896232e6555adc46905 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 12 Jun 2017 16:02:52 -0700 Subject: [PATCH 096/155] Copter: replace hard-coded vertical velocity limit for chute deploy --- ArduCopter/crash_check.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 10111c2026..2df7de4fa9 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -198,6 +198,7 @@ void Copter::parachute_check() const float tilt_angle_limit = attitude_control->get_tilt_limit_rad() + radians(PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG); const float vel_z = -inertial_nav.get_velocity_z()*0.01f; // Convert cm/s to m/s and convert NEU to NED const float vel_z_error = -pos_control->get_vel_error_z()*0.01f; // Convert cm/s to m/s and convert NEU to NED + const float speed_z_excessive_limit_mps = MAX(fabsf(pos_control->get_speed_down()), fabsf(pos_control->get_speed_up()))*0.01f + 1.0f; // Start attitude error timer bool new_angle_error_excessive = angle_error > PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG; @@ -207,7 +208,7 @@ void Copter::parachute_check() parachute_check_state.angle_error_excessive = new_angle_error_excessive; // Start vertical velocity error timer - bool new_vel_z_error_excessive = pos_control->is_active_z() && fabsf(vel_z) > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS && fabsf(vel_z_error) > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS; + bool new_vel_z_error_excessive = pos_control->is_active_z() && fabsf(vel_z) > speed_z_excessive_limit_mps && fabsf(vel_z_error) > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_LIMIT_MPS; if (new_vel_z_error_excessive && !parachute_check_state.vel_z_error_excessive) { parachute_check_state.vel_z_error_excessive_begin_ms = millis(); } From 4a0e495d93413558acf871a61413ee8b4eba737a Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 7 Jul 2017 13:56:34 -0700 Subject: [PATCH 097/155] Copter: add arming check for matternet FTS --- ArduCopter/AP_Arming.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 1a039a2bf8..67c862835d 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -561,6 +561,11 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) } #endif + if (!copter.parachute.get_mttr_prearm_pass()) { + check_failed(true, "FTS state"); + return false; + } + Mode::Number control_mode = copter.control_mode; // always check if the current mode allows arming From 2d170367ab539b9e080d5a268318715bafd9f29a Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 7 Jul 2017 16:45:50 -0700 Subject: [PATCH 098/155] Copter: reset position control during liftoff --- ArduCopter/takeoff.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 4840530adf..db8fd49ba0 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -164,6 +164,9 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) nav_pitch = 0; // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup pos_control->set_limit_accel_xy(); + + wp_nav->shift_wp_origin_to_current_pos(); + wp_nav->wp_and_spline_init(); } else { nav_roll = wp_nav->get_roll(); nav_pitch = wp_nav->get_pitch(); From 096015878c74cd01a4b06781ab6e19c6497dbe9e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 23 Jan 2018 10:05:26 -0800 Subject: [PATCH 099/155] Copter: call auto_takeoff_set_start_alt while waiting to take off --- ArduCopter/mode_guided.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index d6f93dba81..6d593bd430 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -385,6 +385,9 @@ void Mode::auto_takeoff_run() if (!motors->armed() || !copter.ap.auto_armed) { make_safe_spool_down(); wp_nav->shift_wp_origin_to_current_pos(); + + // get initial alt for WP_NAVALT_MIN + copter.auto_takeoff_set_start_alt(); return; } From 5dbd06a0f5a4070adddebb179ecc5eb2dac14a9d Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 23 Mar 2018 16:00:40 -0700 Subject: [PATCH 100/155] Copter: add FS_THR_ENABLED_CONTINUE_MISSION_ALWAYS_LAND --- ArduCopter/defines.h | 1 + ArduCopter/events.cpp | 3 +++ 2 files changed, 4 insertions(+) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 01ac290037..917f90b24f 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -208,6 +208,7 @@ enum HarmonicNotchDynamicMode { #define FS_THR_ENABLED_ALWAYS_LAND 3 #define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL 4 #define FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND 5 +#define FS_THR_ENABLED_CONTINUE_MISSION_ALWAYS_LAND 6 // GCS failsafe definitions (FS_GCS_ENABLE parameter) #define FS_GCS_DISABLED 0 diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 2a56baece3..b6c0bb86fd 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -24,6 +24,9 @@ void Copter::failsafe_radio_on_event() case FS_THR_ENABLED_CONTINUE_MISSION: desired_action = Failsafe_Action_RTL; break; + case FS_THR_ENABLED_CONTINUE_MISSION_ALWAYS_LAND: + desired_action = Failsafe_Action_Land; + break; case FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL: desired_action = Failsafe_Action_SmartRTL; break; From fddf318d192fbf4abc79cf51d81e8aac6e61b9f1 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Fri, 23 Mar 2018 16:10:09 -0700 Subject: [PATCH 101/155] Copter: prevent switches out of manual modes via GCS --- ArduCopter/mode.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 0a5b096dde..0fe587fab9 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -192,7 +192,16 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) return true; } + if (motors->armed() && + (control_mode == Mode::Number::STABILIZE || + control_mode == Mode::Number::ALT_HOLD || + control_mode == Mode::Number::LOITER) && + reason == ModeReason::GCS_COMMAND) { + return false; + } + Mode *new_flightmode = mode_from_mode_num((Mode::Number)mode); + if (new_flightmode == nullptr) { gcs().send_text(MAV_SEVERITY_WARNING,"No such mode"); AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); From 3a287d5d2278959f141e09090355f938c889ec37 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 2 May 2018 12:04:40 -0700 Subject: [PATCH 102/155] Copter: remove pre-arm check on FS_THR_VALUE parameter --- ArduCopter/AP_Arming.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 67c862835d..b29788d458 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -153,7 +153,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) // failsafe parameter checks if (copter.g.failsafe_throttle) { // check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900 - if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) { + if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE"); return false; } From 946c95216c4c1da830cd98aa070d8efa0f422ec5 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 24 May 2018 09:33:39 -0700 Subject: [PATCH 103/155] Copter: prevent descent while centering for precision landing --- ArduCopter/mode.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 0fe587fab9..cee371115d 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -538,6 +538,7 @@ void Mode::land_run_vertical_control(bool pause_descent) #endif // compute desired velocity + const float precland_acceptable_error_high = 100.0f; const float precland_acceptable_error = 15.0f; const float precland_min_descent_speed = 10.0f; @@ -559,11 +560,15 @@ 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 (doing_precision_landing && copter.rangefinder_alt_ok() && copter.rangefinder_state.alt_cm > 35.0f && copter.rangefinder_state.alt_cm < 200.0f) { + if (doing_precision_landing && copter.rangefinder_alt_ok() && copter.rangefinder_state.alt_cm > 35.0f && copter.rangefinder_state.alt_cm < 80.0f) { float max_descent_speed = abs(g.land_speed)*0.5f; float land_slowdown = MAX(0.0f, pos_control->get_horizontal_error()*(max_descent_speed/precland_acceptable_error)); cmb_rate = MIN(-precland_min_descent_speed, -max_descent_speed+land_slowdown); } + + if (doing_precision_landing && pos_control->get_horizontal_error() > precland_acceptable_error_high) { + cmb_rate = -precland_min_descent_speed; + } } // update altitude target and call position controller From 43f286c19369cdb65e7a7590c598c6542eb78dad Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 4 Oct 2018 10:51:57 -0700 Subject: [PATCH 104/155] Copter: reduce land detector trigger time to 0.5 seconds --- ArduCopter/APM_Config.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 74351f33e9..6554e098a5 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -7,6 +7,8 @@ #define RANGEFINDER_WPNAV_FILT_HZ 3.0f +#define LAND_DETECTOR_TRIGGER_SEC 0.5f + // uncomment the lines below to disable features (flash sizes listed are for APM2 boards and will underestimate savings on Pixhawk and other boards) //#define LOGGING_ENABLED DISABLED // disable logging to save 11K of flash space //#define MOUNT DISABLED // disable the camera gimbal to save 8K of flash space From de509d16c844dd1d3e938be8c75d8302fbfc8951 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 14 Nov 2018 09:08:01 -0800 Subject: [PATCH 105/155] Copter: run compass_checks in arming checks --- ArduCopter/AP_Arming.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index b29788d458..78028eff31 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -521,6 +521,10 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) check_failed(display_failure, "EKF-home variance"); return false; } + + if (!compass_checks(display_failure)) { + return false; + } // if we got here all must be ok return true; From 68e9d8766e53488eecb3bc8f0ac7cb79f8cb794a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Mar 2019 15:21:30 +1100 Subject: [PATCH 106/155] Copter: use ARMING_CHECK_FTS and don't check it if parachute disabled --- ArduCopter/AP_Arming.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 78028eff31..4de1b2ba91 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -565,9 +565,11 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) } #endif - if (!copter.parachute.get_mttr_prearm_pass()) { - check_failed(true, "FTS state"); - return false; + if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_FTS)) { + if (copter.parachute.enabled() && !copter.parachute.get_mttr_prearm_pass()) { + check_failed(true, "FTS state"); + return false; + } } Mode::Number control_mode = copter.control_mode; From 7dab0e0f0c32248dc80b97c35f014344be7b5c8a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Mar 2019 15:21:46 +1100 Subject: [PATCH 107/155] Copter: display an error msg on manual mode refusal --- ArduCopter/mode.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index cee371115d..ce4dcd0012 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -197,6 +197,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) control_mode == Mode::Number::ALT_HOLD || control_mode == Mode::Number::LOITER) && reason == ModeReason::GCS_COMMAND) { + gcs().send_text(MAV_SEVERITY_WARNING,"Refusing GCS mode change"); return false; } From ee5bea08c96aef7dad1448c153606c20b7db9058 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2019 12:14:53 +1000 Subject: [PATCH 108/155] Copter: added max navigation alt WP_NAVALT_MAX this gives us 3 regions of takeoff: 1) below WP_NAVALT_MIN no roll/pitch is allowed 2) between WP_NAVALT_MIN and WP_NAVALT_MAX a linear interpolation of allowed lean angle is used 3) at WP_NAVALT_MAX and above rull range of attitude is allowed by setting WP_NAVALT_MAX above the height of obstacles that may interfere with GPS we can avoid GPS errors on takeoff. It will however limit the amount of wind that can be handled on takeoff --- ArduCopter/Parameters.cpp | 9 +++++++-- ArduCopter/Parameters.h | 3 +++ ArduCopter/mode.h | 1 + ArduCopter/takeoff.cpp | 32 ++++++++++++++++++++++++-------- 4 files changed, 35 insertions(+), 10 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 0e331dadb1..15d255d643 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -961,8 +961,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(arot, "AROT_", 37, ParametersG2, AC_Autorotation), #endif - - + // @Param: WP_NAVALT_MAX + // @DisplayName: Maximum navigation altitude + // @Description: This is the altitude in meters above which full navigation attitude can begin. This applies in auto takeoff + // @Range: 0 5 + // @User: Standard + AP_GROUPINFO("WP_NAVALT_MAX", 38, ParametersG2, wp_navalt_max, 0), + AP_GROUPEND }; diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index bc0dc53c6a..9160bf87e1 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -485,6 +485,9 @@ class ParametersG2 { // altitude at which nav control can start in takeoff AP_Float wp_navalt_min; + // altitude at which nav control reaches full range in takeoff + AP_Float wp_navalt_max; + #if BUTTON_ENABLED == ENABLED // button checking AP_Button button; diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index e9e1d2dac6..a28fe32493 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -172,6 +172,7 @@ class Mode { void auto_takeoff_attitude_run(float target_yaw_rate); // altitude below which we do no navigation in auto takeoff static float auto_takeoff_no_nav_alt_cm; + static float auto_takeoff_max_nav_alt_cm; public: // Navigation Yaw control diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index db8fd49ba0..c171b55013 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -142,10 +142,13 @@ void Mode::auto_takeoff_set_start_alt(void) { // start with our current altitude auto_takeoff_no_nav_alt_cm = inertial_nav.get_altitude(); - + auto_takeoff_max_nav_alt_cm = inertial_nav.get_altitude(); + if (is_disarmed_or_landed() || !motors->get_interlock()) { // we are not flying, add the wp_navalt_min auto_takeoff_no_nav_alt_cm += g2.wp_navalt_min * 100; + auto_takeoff_max_nav_alt_cm += g2.wp_navalt_max * 100; + auto_takeoff_max_nav_alt_cm = MAX(auto_takeoff_max_nav_alt_cm,auto_takeoff_no_nav_alt_cm); } } @@ -157,19 +160,32 @@ void Mode::auto_takeoff_set_start_alt(void) void Mode::auto_takeoff_attitude_run(float target_yaw_rate) { float nav_roll, nav_pitch; - - if (g2.wp_navalt_min > 0 && inertial_nav.get_altitude() < auto_takeoff_no_nav_alt_cm) { - // we haven't reached the takeoff navigation altitude yet + + nav_roll = wp_nav->get_roll(); + nav_pitch = wp_nav->get_pitch(); + + float alt_cm = inertial_nav.get_altitude(); + if (g2.wp_navalt_min > 0 && alt_cm <= auto_takeoff_no_nav_alt_cm) { + // below no nav alt we zero roll and pitch demand nav_roll = 0; nav_pitch = 0; // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup pos_control->set_limit_accel_xy(); wp_nav->shift_wp_origin_to_current_pos(); - wp_nav->wp_and_spline_init(); - } else { - nav_roll = wp_nav->get_roll(); - nav_pitch = wp_nav->get_pitch(); + } else if (g2.wp_navalt_min > 0 && alt_cm < auto_takeoff_max_nav_alt_cm) { + // between no nav alt and max nav alt we interpolate + // roll/pitch demand + float lean_limit = linear_interpolate(0, aparm.angle_max, + alt_cm, + auto_takeoff_no_nav_alt_cm, auto_takeoff_max_nav_alt_cm); + if (fabsf(nav_roll) > lean_limit || + fabsf(nav_pitch) > lean_limit) { + nav_roll = constrain_float(nav_roll, -lean_limit, lean_limit); + nav_pitch = constrain_float(nav_pitch, -lean_limit, lean_limit); + // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup + pos_control->set_limit_accel_xy(); + } } // roll & pitch from waypoint controller, yaw rate from pilot From 57a1d59f5097adb6ea68eed6d188f74c7a168966 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2019 12:17:17 +1000 Subject: [PATCH 109/155] Copter: added Matternet specific GPS pre-takeoff and pre-arm checks ensure that position has not moved significantly between arming and auto-takeoff Also provide stricter checking on GPS reported hacc and vacc when arming These are in a new matternet specific parameter block to reduce the chances of conflict and ID number changes with rebase on newer ArduPilot releases --- ArduCopter/AP_Arming.cpp | 44 ++++++++++++++++++++++++++++ ArduCopter/AP_Arming.h | 3 ++ ArduCopter/Copter.h | 2 ++ ArduCopter/GCS_Mavlink.cpp | 6 ++++ ArduCopter/Parameters.cpp | 59 ++++++++++++++++++++++++++++++++++++++ ArduCopter/Parameters.h | 19 +++++++++++- 6 files changed, 132 insertions(+), 1 deletion(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 4de1b2ba91..1e020e6ffe 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -379,6 +379,27 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) return false; } + float hacc, vacc; + if (!copter.gps.horizontal_accuracy(hacc) || + !copter.gps.vertical_accuracy(vacc)) { + if (display_failure) { + gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: No GPS accuracy"); + } + return false; + } + if (hacc > copter.matternet.arm_gps_hacc) { + if (display_failure) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: GPS hacc %.2f", hacc); + } + return false; + } + if (vacc > copter.matternet.arm_gps_vacc) { + if (display_failure) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: GPS vacc %.2f", vacc); + } + return false; + } + // if we got here all must be ok AP_Notify::flags.pre_arm_gps_check = true; return true; @@ -856,3 +877,26 @@ bool AP_Arming_Copter::disarm() return true; } + + +/* + checks run before takeoff to check that GPS movement is within + acceptable range + */ +bool AP_Arming_Copter::pre_takeoff_checks(void) +{ + float pos_change, alt_change; + if (!copter.gps.get_pre_arm_pos_change(pos_change, alt_change)) { + gcs().send_text(MAV_SEVERITY_CRITICAL,"Takeoff: no GPS data"); + return false; + } + if (pos_change > copter.matternet.tkoff_gps_pos_change) { + gcs().send_text(MAV_SEVERITY_CRITICAL,"Takeoff: pos change %.2f", pos_change); + return false; + } + if (fabsf(alt_change) > copter.matternet.tkoff_gps_alt_change) { + gcs().send_text(MAV_SEVERITY_CRITICAL,"Takeoff: alt change %.2f", alt_change); + return false; + } + return true; +} diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index 69962530d3..c437e02de9 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -26,6 +26,9 @@ class AP_Arming_Copter : public AP_Arming bool disarm() override; bool arm(AP_Arming::Method method, bool do_arming_checks=true) override; + // checks run before auto-takeoff on MISSION_START allowed + bool pre_takeoff_checks(void); + protected: bool pre_arm_checks(bool display_failure) override; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index af0efc650e..50c7de0f56 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -198,6 +198,7 @@ class Copter : public AP_Vehicle { friend class AP_Rally_Copter; friend class Parameters; friend class ParametersG2; + friend class ParametersMTTR; friend class AP_Avoidance_Copter; #if ADVANCED_FAILSAFE == ENABLED @@ -252,6 +253,7 @@ class Copter : public AP_Vehicle { // Global parameters are all contained within the 'g' class. Parameters g; ParametersG2 g2; + ParametersMTTR matternet; // main loop scheduler AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)}; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index c6c8928cc0..3b6b9a71b7 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -713,6 +713,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ #if MODE_AUTO_ENABLED == ENABLED case MAV_CMD_MISSION_START: + // when we are not yet flying we run additional + // pre-takeoff checks for GPS movement + if (copter.motors->get_desired_spool_state() < AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED && + !copter.arming.pre_takeoff_checks()) { + return MAV_RESULT_FAILED; + } if (copter.motors->armed() && copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) { copter.set_auto_armed(true); diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 15d255d643..3486390c6b 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -717,6 +717,10 @@ const AP_Param::Info Copter::var_info[] = { // @Path: Parameters.cpp GOBJECT(g2, "", ParametersG2), + // @Group: + // @Path: Parameters.cpp + GOBJECT(matternet, "", ParametersMTTR), + AP_VAREND }; @@ -964,6 +968,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: WP_NAVALT_MAX // @DisplayName: Maximum navigation altitude // @Description: This is the altitude in meters above which full navigation attitude can begin. This applies in auto takeoff + // @Units: m // @Range: 0 5 // @User: Standard AP_GROUPINFO("WP_NAVALT_MAX", 38, ParametersG2, wp_navalt_max, 0), @@ -1061,6 +1066,60 @@ ParametersG2::ParametersG2(void) AP_Param::setup_object_defaults(this, var_info); } + +/* + Matternet specific parameters + */ +const AP_Param::GroupInfo ParametersMTTR::var_info[] = { + + // @Param: TOFF_POS_CHANGE + // @DisplayName: Maximum GPS pos change + // @Description: This is the maximum allowed position change since arming for automatic takeoff + // @Units: m + // @Range: 0 5 + // @Increment: 0.01 + // @User: Advanced + AP_GROUPINFO("TOFF_POS_CHANGE", 1, ParametersMTTR, tkoff_gps_pos_change, 1.0), + + // @Param: TOFF_ALT_CHANGE + // @DisplayName: Maximum GPS alt change + // @Description: This is the maximum allowed altitude change since arming for automatic takeoff + // @Units: m + // @Range: 0 5 + // @Increment: 0.01 + // @User: Advanced + AP_GROUPINFO("TOFF_ALT_CHANGE", 2, ParametersMTTR, tkoff_gps_alt_change, 1.0), + + // @Param: ARM_GPS_HACC + // @DisplayName: Maximum GPS HAcc on arming + // @Description: This is the maximum allowed GPS horizontal accuracy for arming + // @Units: m + // @Range: 0 5 + // @Increment: 0.01 + // @User: Advanced + AP_GROUPINFO("ARM_GPS_HACC", 3, ParametersMTTR, arm_gps_hacc, 1.0), + + // @Param: ARM_GPS_VACC + // @DisplayName: Maximum GPS VAcc on arming + // @Description: This is the maximum allowed GPS vertical accuracy for arming + // @Units: m + // @Range: 0 5 + // @Increment: 0.01 + // @User: Advanced + AP_GROUPINFO("ARM_GPS_VACC", 4, ParametersMTTR, arm_gps_vacc, 1.0), + + AP_GROUPEND +}; + +/* + constructor for matternet object + */ +ParametersMTTR::ParametersMTTR(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + + /* This is a conversion table from old parameter values to new parameter names. The startup code looks for saved values of the old diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 9160bf87e1..0c68e4d879 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -53,7 +53,7 @@ class Parameters { k_param_software_type, // deprecated k_param_ins_old, // *** Deprecated, remove with next eeprom number change k_param_ins, // libraries/AP_InertialSensor variables - k_param_NavEKF2_old, // deprecated - remove + k_param_matternet, k_param_NavEKF2, k_param_g2, // 2nd block of parameters k_param_NavEKF3, @@ -625,4 +625,21 @@ class ParametersG2 { #endif }; +/* + Matternet specific parameters. This is done as a separate block to + reduce the change of conflict on rebase + */ +class ParametersMTTR { +public: + ParametersMTTR(void); + + // var_info for holding Parameter information + static const struct AP_Param::GroupInfo var_info[]; + + AP_Float tkoff_gps_pos_change; + AP_Float tkoff_gps_alt_change; + AP_Float arm_gps_hacc; + AP_Float arm_gps_vacc; +}; + extern const AP_Param::Info var_info[]; From fb6909565ed67c830787e108cccbc77acdabd01e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 25 Apr 2019 11:14:41 +1000 Subject: [PATCH 110/155] Copter: zero rate integrators below WP_NAVALT_MIN on takeoff this prevents an overshoot due to small AHRS_TRIM_[XY] errors in the vehicle causing a small attitude deviation on takeoff --- ArduCopter/takeoff.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index c171b55013..3f0905cb09 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -172,6 +172,11 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup pos_control->set_limit_accel_xy(); + // clear rate integrators till we reach min navigation altitude + attitude_control->get_rate_roll_pid().set_integrator(0); + attitude_control->get_rate_pitch_pid().set_integrator(0); + attitude_control->get_rate_yaw_pid().set_integrator(0); + wp_nav->shift_wp_origin_to_current_pos(); } else if (g2.wp_navalt_min > 0 && alt_cm < auto_takeoff_max_nav_alt_cm) { // between no nav alt and max nav alt we interpolate From 389f40e0aaadbdde59caf05e32eaeffc2fad5bf3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2019 10:49:32 +1000 Subject: [PATCH 111/155] Copter: added a liftoff detector in auto takeoff we detect liftoff using a combination of the baro "dip" caused by downthrust of the motors and the throttle level relative to hover throttle this introduces two new parameters: TOFF_BARO_DIP - the amount of rise from minimum of barometer to detect liftoff TOFF_HOV_PCT - the percentage of hover throttle needed for liftoff --- ArduCopter/Copter.h | 5 +++++ ArduCopter/Parameters.cpp | 18 +++++++++++++++ ArduCopter/Parameters.h | 2 ++ ArduCopter/takeoff.cpp | 46 +++++++++++++++++++++++++++++++++++++-- 4 files changed, 69 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 50c7de0f56..e9ebea9ca0 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -402,6 +402,11 @@ class Copter : public AP_Vehicle { Mode::Number prev_control_mode; ModeReason prev_control_mode_reason = ModeReason::UNKNOWN; + // minimum recorded barometric alt during takeoff. Used to detect + // the "dip" in barometric alt that happens on takeoff + float takeoff_baro_min_alt_m; + bool takeoff_liftoff_complete; + RCMapper rcmap; // intertial nav alt when we armed diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 3486390c6b..e169c46a2c 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1107,6 +1107,24 @@ const AP_Param::GroupInfo ParametersMTTR::var_info[] = { // @Increment: 0.01 // @User: Advanced AP_GROUPINFO("ARM_GPS_VACC", 4, ParametersMTTR, arm_gps_vacc, 1.0), + + // @Param: TOFF_BARO_DIP + // @DisplayName: Barometric rise for liftoff completion + // @Description: This is amount of rise in barometer above min reading in takeoff before we consider that liftoff has completed + // @Units: m + // @Range: 0 5 + // @Increment: 0.01 + // @User: Advanced + AP_GROUPINFO("TOFF_BARO_DIP", 5, ParametersMTTR, tkoff_baro_dip, 2.0), + + // @Param: TOFF_HOV_PCT + // @DisplayName: Percent of hover throttle for liftoff + // @Description: This is percentage of hover throttle before we consider that liftoff is complete + // @Units: % + // @Range: 0 127 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("TOFF_HOV_PCT", 6, ParametersMTTR, tkoff_hover_pct, 80), AP_GROUPEND }; diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 0c68e4d879..403019c8b8 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -640,6 +640,8 @@ class ParametersMTTR { AP_Float tkoff_gps_alt_change; AP_Float arm_gps_hacc; AP_Float arm_gps_vacc; + AP_Float tkoff_baro_dip; + AP_Int8 tkoff_hover_pct; }; extern const AP_Param::Info var_info[]; diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 3f0905cb09..ccd150c231 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -150,6 +150,10 @@ void Mode::auto_takeoff_set_start_alt(void) auto_takeoff_max_nav_alt_cm += g2.wp_navalt_max * 100; auto_takeoff_max_nav_alt_cm = MAX(auto_takeoff_max_nav_alt_cm,auto_takeoff_no_nav_alt_cm); } + + // reset the min baro alt seen in takeoff + takeoff_baro_min_alt_m = barometer.get_altitude(); + takeoff_liftoff_complete = false; } @@ -164,8 +168,44 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) nav_roll = wp_nav->get_roll(); nav_pitch = wp_nav->get_pitch(); + /* + record the minimum barometer altitude we see in the + takeoff. This is used to detect the "dip" that happens on the + baro when the motors start applying thrust. + */ + float barometer_alt = barometer.get_altitude(); + if (barometer_alt < takeoff_baro_min_alt_m) { + takeoff_baro_min_alt_m = barometer_alt; + } + + /* + check conditions for liftoff completion + We consider liftoff to be completed under one of 3 conditions: + 1) the TOFF_BARO_DIP and TOFF_HOV_PCT are both zero + 2) the barometric height has risen from the minimum by at least TOFF_BARO_DIP + 2) the throttle has reached TOFF_HOV_PCT of the hover throttle + */ + if (!takeoff_liftoff_complete) { + if (copter.matternet.tkoff_baro_dip > 0 && + barometer_alt - takeoff_baro_min_alt_m >= copter.matternet.tkoff_baro_dip) { + takeoff_liftoff_complete = true; + gcs().send_text(MAV_SEVERITY_INFO, "LIFTOFF: baro %.1f thr=%.2f\n", barometer_alt - takeoff_baro_min_alt_m, motors->get_throttle()); + } + if (copter.matternet.tkoff_hover_pct > 0 && + motors->get_throttle() >= copter.matternet.tkoff_hover_pct * 0.01 * motors->get_throttle_hover()) { + takeoff_liftoff_complete = true; + gcs().send_text(MAV_SEVERITY_INFO, "LIFTOFF: throttle %.2f baro=%.1f\n", motors->get_throttle(), barometer_alt - takeoff_baro_min_alt_m); + } + if (copter.matternet.tkoff_baro_dip <= 0 && + copter.matternet.tkoff_hover_pct <= 0) { + // both are disabled, do direct takeoff + takeoff_liftoff_complete = true; + } + } + + float alt_cm = inertial_nav.get_altitude(); - if (g2.wp_navalt_min > 0 && alt_cm <= auto_takeoff_no_nav_alt_cm) { + if (!takeoff_liftoff_complete) { // below no nav alt we zero roll and pitch demand nav_roll = 0; nav_pitch = 0; @@ -178,7 +218,9 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) attitude_control->get_rate_yaw_pid().set_integrator(0); wp_nav->shift_wp_origin_to_current_pos(); - } else if (g2.wp_navalt_min > 0 && alt_cm < auto_takeoff_max_nav_alt_cm) { + + auto_takeoff_max_nav_alt_cm = alt_cm + g2.wp_navalt_max * 100; + } else if (g2.wp_navalt_max > 0 && alt_cm < auto_takeoff_max_nav_alt_cm) { // between no nav alt and max nav alt we interpolate // roll/pitch demand float lean_limit = linear_interpolate(0, aparm.angle_max, From 2c5f25edca6d7528dbbef86145433fe2ac2f2533 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 18:04:13 +1100 Subject: [PATCH 112/155] Copter: fixed takeoff checks --- ArduCopter/mode_guided.cpp | 2 +- ArduCopter/takeoff.cpp | 28 ++++++++++++++-------------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 6d593bd430..811ac984a4 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -387,7 +387,7 @@ void Mode::auto_takeoff_run() wp_nav->shift_wp_origin_to_current_pos(); // get initial alt for WP_NAVALT_MIN - copter.auto_takeoff_set_start_alt(); + auto_takeoff_set_start_alt(); return; } diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index ccd150c231..b569a4b7de 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -152,8 +152,8 @@ void Mode::auto_takeoff_set_start_alt(void) } // reset the min baro alt seen in takeoff - takeoff_baro_min_alt_m = barometer.get_altitude(); - takeoff_liftoff_complete = false; + copter.takeoff_baro_min_alt_m = copter.barometer.get_altitude(); + copter.takeoff_liftoff_complete = false; } @@ -173,9 +173,9 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) takeoff. This is used to detect the "dip" that happens on the baro when the motors start applying thrust. */ - float barometer_alt = barometer.get_altitude(); - if (barometer_alt < takeoff_baro_min_alt_m) { - takeoff_baro_min_alt_m = barometer_alt; + float barometer_alt = copter.barometer.get_altitude(); + if (barometer_alt < copter.takeoff_baro_min_alt_m) { + copter.takeoff_baro_min_alt_m = barometer_alt; } /* @@ -185,27 +185,27 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) 2) the barometric height has risen from the minimum by at least TOFF_BARO_DIP 2) the throttle has reached TOFF_HOV_PCT of the hover throttle */ - if (!takeoff_liftoff_complete) { + if (!copter.takeoff_liftoff_complete) { if (copter.matternet.tkoff_baro_dip > 0 && - barometer_alt - takeoff_baro_min_alt_m >= copter.matternet.tkoff_baro_dip) { - takeoff_liftoff_complete = true; - gcs().send_text(MAV_SEVERITY_INFO, "LIFTOFF: baro %.1f thr=%.2f\n", barometer_alt - takeoff_baro_min_alt_m, motors->get_throttle()); + barometer_alt - copter.takeoff_baro_min_alt_m >= copter.matternet.tkoff_baro_dip) { + copter.takeoff_liftoff_complete = true; + gcs().send_text(MAV_SEVERITY_INFO, "LIFTOFF: baro %.1f thr=%.2f\n", barometer_alt - copter.takeoff_baro_min_alt_m, motors->get_throttle()); } if (copter.matternet.tkoff_hover_pct > 0 && motors->get_throttle() >= copter.matternet.tkoff_hover_pct * 0.01 * motors->get_throttle_hover()) { - takeoff_liftoff_complete = true; - gcs().send_text(MAV_SEVERITY_INFO, "LIFTOFF: throttle %.2f baro=%.1f\n", motors->get_throttle(), barometer_alt - takeoff_baro_min_alt_m); + copter.takeoff_liftoff_complete = true; + gcs().send_text(MAV_SEVERITY_INFO, "LIFTOFF: throttle %.2f baro=%.1f\n", motors->get_throttle(), barometer_alt - copter.takeoff_baro_min_alt_m); } if (copter.matternet.tkoff_baro_dip <= 0 && copter.matternet.tkoff_hover_pct <= 0) { // both are disabled, do direct takeoff - takeoff_liftoff_complete = true; + copter.takeoff_liftoff_complete = true; } } float alt_cm = inertial_nav.get_altitude(); - if (!takeoff_liftoff_complete) { + if (!copter.takeoff_liftoff_complete) { // below no nav alt we zero roll and pitch demand nav_roll = 0; nav_pitch = 0; @@ -223,7 +223,7 @@ void Mode::auto_takeoff_attitude_run(float target_yaw_rate) } else if (g2.wp_navalt_max > 0 && alt_cm < auto_takeoff_max_nav_alt_cm) { // between no nav alt and max nav alt we interpolate // roll/pitch demand - float lean_limit = linear_interpolate(0, aparm.angle_max, + float lean_limit = linear_interpolate(0, copter.aparm.angle_max, alt_cm, auto_takeoff_no_nav_alt_cm, auto_takeoff_max_nav_alt_cm); if (fabsf(nav_roll) > lean_limit || From adf015ddd5d648afc6a148acaf11e2b439c713b2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 7 May 2019 08:17:44 +1000 Subject: [PATCH 113/155] Copter: added ARMED_PIN this is a pin setting for an armed indicator. The pin goes high when armed, low when disarmed --- ArduCopter/AP_Arming.cpp | 5 +++++ ArduCopter/Copter.h | 2 ++ ArduCopter/Parameters.cpp | 8 ++++++++ ArduCopter/Parameters.h | 1 + ArduCopter/compassmot.cpp | 2 ++ ArduCopter/esc_calibration.cpp | 1 + ArduCopter/failsafe.cpp | 1 + ArduCopter/motor_test.cpp | 3 +++ ArduCopter/system.cpp | 12 ++++++++++++ 9 files changed, 35 insertions(+) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 1e020e6ffe..736751f00b 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -13,6 +13,8 @@ void AP_Arming_Copter::update(void) } pre_arm_checks(display_fail); + + copter.update_armed_pin(); } bool AP_Arming_Copter::pre_arm_checks(bool display_failure) @@ -788,6 +790,8 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ // finally actually arm the motors copter.motors->armed(true); + copter.update_armed_pin(); + AP::logger().Write_Event(DATA_ARMED); // log flight mode in case it was changed while vehicle was disarmed @@ -861,6 +865,7 @@ bool AP_Arming_Copter::disarm() // send disarm command to motors copter.motors->armed(false); + copter.update_armed_pin(); #if MODE_AUTO_ENABLED == ENABLED // reset the mission diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e9ebea9ca0..f092b96e07 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -255,6 +255,8 @@ class Copter : public AP_Vehicle { ParametersG2 g2; ParametersMTTR matternet; + void update_armed_pin(); + // main loop scheduler AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)}; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index e169c46a2c..7ba18105cd 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1125,6 +1125,14 @@ const AP_Param::GroupInfo ParametersMTTR::var_info[] = { // @Increment: 1 // @User: Advanced AP_GROUPINFO("TOFF_HOV_PCT", 6, ParametersMTTR, tkoff_hover_pct, 80), + + // @Param: ARM_PIN + // @DisplayName: Pin number for armed state + // @Description: If set to value >= 0 then this pin will go high on arming and low on disarm + // @Range: -1 127 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("ARMED_PIN", 7, ParametersMTTR, arm_pin, -1), AP_GROUPEND }; diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 403019c8b8..9853b91e92 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -642,6 +642,7 @@ class ParametersMTTR { AP_Float arm_gps_vacc; AP_Float tkoff_baro_dip; AP_Int8 tkoff_hover_pct; + AP_Int8 arm_pin; }; extern const AP_Param::Info var_info[]; diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 8795e83f45..76b0b25910 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -125,6 +125,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) init_rc_out(); enable_motor_output(); motors->armed(true); + update_armed_pin(); hal.util->set_soft_armed(true); // initialise run time @@ -231,6 +232,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) // stop motors motors->output_min(); motors->armed(false); + update_armed_pin(); hal.util->set_soft_armed(false); // set and save motor compensation diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index 152388d1ed..b1a5f226b2 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -178,6 +178,7 @@ void Copter::esc_calibration_setup() // arm and enable motors motors->armed(true); + update_armed_pin(); SRV_Channels::enable_by_mask(motors->get_motor_mask()); hal.util->set_soft_armed(true); } diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index c3ee045c88..e14746440b 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -66,6 +66,7 @@ void Copter::failsafe_check() failsafe_last_timestamp = tnow; if(motors->armed()) { motors->armed(false); + update_armed_pin(); motors->output(); } } diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index c403852b3c..ab55b164ba 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -41,6 +41,7 @@ void Copter::motor_test_output() motor_test_start_ms = now; if (!motors->armed()) { motors->armed(true); + update_armed_pin(); hal.util->set_soft_armed(true); } } @@ -153,6 +154,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t init_rc_out(); enable_motor_output(); motors->armed(true); + update_armed_pin(); hal.util->set_soft_armed(true); } @@ -199,6 +201,7 @@ void Copter::motor_test_stop() // disarm motors motors->armed(false); + update_armed_pin(); hal.util->set_soft_armed(false); // reset timeout diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index f5152e505a..aa1c592be1 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -686,3 +686,15 @@ bool Copter::is_tradheli() const return false; #endif } + + +/* + update arming pin set with ARM_PIN, if any + */ +void Copter::update_armed_pin(void) +{ + if (matternet.arm_pin != -1) { + hal.gpio->pinMode(matternet.arm_pin, HAL_GPIO_OUTPUT); + hal.gpio->write(matternet.arm_pin, motors->armed()); + } +} From 2b3a626a1079e3aae1adebaaaeef3a27d58c733e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 8 May 2019 09:39:01 +1000 Subject: [PATCH 114/155] Copter: disable RC arming check in GUIDED mode allow for auto missions with no RC --- ArduCopter/AP_Arming.cpp | 5 ++++- ArduCopter/mode.cpp | 3 +++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 736751f00b..044a8274fb 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -286,6 +286,9 @@ bool AP_Arming_Copter::motor_checks(bool display_failure) bool AP_Arming_Copter::pilot_throttle_checks(bool display_failure) { + if (rc_check_disabled) { + return true; + } // check throttle is above failsafe throttle // this is near the bottom to allow other failures to be displayed before checking pilot throttle if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) { @@ -649,7 +652,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) #endif // check throttle - if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) { + if (((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RC)) && !rc_check_disabled) { #if FRAME_CONFIG == HELI_FRAME const char *rc_item = "Collective"; #else diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index ce4dcd0012..fc26e1cc65 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -303,6 +303,9 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) // update notify object notify_flight_mode(); + // we want to allow arming with no RC in GUIDED mode + arming.disable_RC_check(mode == GUIDED); + // return success return true; } From 73a75f47748d28d75e7bfefa100a18bc7caf5db1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 8 May 2019 09:57:38 +1000 Subject: [PATCH 115/155] Copter: prevent double arm with RC failsafe off --- ArduCopter/events.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index b6c0bb86fd..4a51a6dbc6 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -339,7 +339,7 @@ void Copter::set_mode_SmartRTL_or_RTL(ModeReason reason) } bool Copter::should_disarm_on_failsafe() { - if (ap.in_arming_delay) { + if (ap.in_arming_delay && control_mode != GUIDED) { return true; } @@ -351,6 +351,14 @@ bool Copter::should_disarm_on_failsafe() { case Mode::Number::AUTO: // if mission has not started AND vehicle is landed, disarm motors return !ap.auto_armed && ap.land_complete; + case GUIDED: + if (g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION || + g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION_ALWAYS_LAND) { + // prevent needing to arm twice in GUIDED + return false; + } + return ap.land_complete; + default: // used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold // if landed disarm From 79291f1fa407b71b95101c7d522f543339be427c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 8 Jun 2019 07:58:05 +1000 Subject: [PATCH 116/155] Copter: don't show failed system status with RC off in GUIDED or AUTO --- ArduCopter/Copter.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index f092b96e07..ae9affc8c8 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -430,7 +430,11 @@ class Copter : public AP_Vehicle { } failsafe; bool any_failsafe_triggered() const { - return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb; + bool ret = battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb; + if (control_mode != GUIDED && control_mode != AUTO) { + ret |= failsafe.radio; + } + return ret; } // sensor health for logging From 24fccd8aef39f27a629a8f5afc541c1d25d7f848 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 11 Jun 2019 08:13:52 +1000 Subject: [PATCH 117/155] Copter: notify logging of arming failure --- ArduCopter/AP_Arming.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 044a8274fb..8577bef113 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -727,6 +727,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ if (!AP_Arming::arm(method, do_arming_checks)) { AP_Notify::events.arming_failed = true; in_arm_motors = false; + AP::logger().arming_failure(); return false; } From 565ffded6537527b54240f79a65ab1a200db89bc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 21 Jul 2019 19:43:22 +1000 Subject: [PATCH 118/155] Copter: implement LandIfManual battery failsafe option this will land if in a manually controlled mode, and continue otherwise --- ArduCopter/Copter.cpp | 2 +- ArduCopter/Copter.h | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 0f246a5968..d6b6ecd17f 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -206,7 +206,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #endif }; -constexpr int8_t Copter::_failsafe_priorities[7]; +constexpr int8_t Copter::_failsafe_priorities[8]; void Copter::setup() { diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index ae9affc8c8..206e5c1587 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -642,7 +642,8 @@ class Copter : public AP_Vehicle { Failsafe_Action_RTL = 2, Failsafe_Action_SmartRTL = 3, Failsafe_Action_SmartRTL_Land = 4, - Failsafe_Action_Terminate = 5 + Failsafe_Action_Terminate = 5, + Failsafe_Action_LandIfManual = 6 }; enum class FailsafeOption { @@ -656,6 +657,7 @@ class Copter : public AP_Vehicle { static constexpr int8_t _failsafe_priorities[] = { Failsafe_Action_Terminate, Failsafe_Action_Land, + Failsafe_Action_LandIfManual, Failsafe_Action_RTL, Failsafe_Action_SmartRTL_Land, Failsafe_Action_SmartRTL, From 435eb6bcbee050fbb51050e0a9e82c19081119db Mon Sep 17 00:00:00 2001 From: AkshayMatternet Date: Wed, 28 Aug 2019 13:07:29 -0700 Subject: [PATCH 119/155] Copter: Prevent from going to Radio failsafe if in BRAKE mode --- ArduCopter/Copter.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 206e5c1587..b14d43cf4c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -431,7 +431,7 @@ class Copter : public AP_Vehicle { bool any_failsafe_triggered() const { bool ret = battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb; - if (control_mode != GUIDED && control_mode != AUTO) { + if (control_mode != GUIDED && control_mode != AUTO && control_mode != BRAKE) { ret |= failsafe.radio; } return ret; From f6a3814c74a119580f1e9123039d05cb4154270d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Nov 2019 10:17:12 +1100 Subject: [PATCH 120/155] Copter: add clearer message on takeoff attempt while disarmed --- ArduCopter/AP_Arming.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 8577bef113..d110039fdb 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -894,6 +894,10 @@ bool AP_Arming_Copter::disarm() */ bool AP_Arming_Copter::pre_takeoff_checks(void) { + if (!hal.util->get_soft_armed()) { + gcs().send_text(MAV_SEVERITY_CRITICAL,"Takeoff: not armed"); + return false; + } float pos_change, alt_change; if (!copter.gps.get_pre_arm_pos_change(pos_change, alt_change)) { gcs().send_text(MAV_SEVERITY_CRITICAL,"Takeoff: no GPS data"); From e9480fd392ccedeb1d91199b46540073e8e6173e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 18 Dec 2019 09:44:40 +1100 Subject: [PATCH 121/155] Copter: set MAV_SYS_STATUS_PREARM_CHECK this allows the GCS to continually monitor prearm check status --- ArduCopter/GCS_Copter.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/GCS_Copter.cpp b/ArduCopter/GCS_Copter.cpp index 75eeda4ab8..3d28280d8f 100644 --- a/ArduCopter/GCS_Copter.cpp +++ b/ArduCopter/GCS_Copter.cpp @@ -166,4 +166,14 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void) } } #endif + + // give GCS status of prearm checks. This is enabled if any arming checks are enabled. + // it is healthy if armed or checks are passing + control_sensors_present |= MAV_SYS_STATUS_PREARM_CHECK; + if (copter.arming.get_enabled_checks()) { + control_sensors_enabled |= MAV_SYS_STATUS_PREARM_CHECK; + if (hal.util->get_soft_armed() || AP_Notify::flags.pre_arm_check) { + control_sensors_health |= MAV_SYS_STATUS_PREARM_CHECK; + } + } } From 454ff99efbd1a7dcf77f08f9e580b3ca5b4ce091 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 17:58:44 +1100 Subject: [PATCH 122/155] Copter: fixed new mode number style --- ArduCopter/Copter.h | 2 +- ArduCopter/events.cpp | 4 ++-- ArduCopter/mode.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index b14d43cf4c..63c858e166 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -431,7 +431,7 @@ class Copter : public AP_Vehicle { bool any_failsafe_triggered() const { bool ret = battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb; - if (control_mode != GUIDED && control_mode != AUTO && control_mode != BRAKE) { + if (control_mode != Mode::Number::GUIDED && control_mode != Mode::Number::AUTO && control_mode != Mode::Number::BRAKE) { ret |= failsafe.radio; } return ret; diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 4a51a6dbc6..2a89ee52eb 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -339,7 +339,7 @@ void Copter::set_mode_SmartRTL_or_RTL(ModeReason reason) } bool Copter::should_disarm_on_failsafe() { - if (ap.in_arming_delay && control_mode != GUIDED) { + if (ap.in_arming_delay && control_mode != Mode::Number::GUIDED) { return true; } @@ -351,7 +351,7 @@ bool Copter::should_disarm_on_failsafe() { case Mode::Number::AUTO: // if mission has not started AND vehicle is landed, disarm motors return !ap.auto_armed && ap.land_complete; - case GUIDED: + case Mode::Number::GUIDED: if (g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION || g.failsafe_throttle == FS_THR_ENABLED_CONTINUE_MISSION_ALWAYS_LAND) { // prevent needing to arm twice in GUIDED diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index fc26e1cc65..3d291db2db 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -304,7 +304,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) notify_flight_mode(); // we want to allow arming with no RC in GUIDED mode - arming.disable_RC_check(mode == GUIDED); + arming.disable_RC_check(mode == Mode::Number::GUIDED); // return success return true; From c0cb46045ffe58cd5c82c142f58638017ef932d0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 18:01:02 +1100 Subject: [PATCH 123/155] Copter: fixed parachute checks --- ArduCopter/crash_check.cpp | 15 ++++++--------- ArduCopter/ekf_check.cpp | 2 +- 2 files changed, 7 insertions(+), 10 deletions(-) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 2df7de4fa9..2628b27415 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -175,19 +175,16 @@ void Copter::parachute_check() // return immediately if motors are not armed or pilot's throttle is above zero if (!motors->armed()) { - control_loss_count = 0; return; } // return immediately if we are not in an angle stabilize flight mode or we are flipping if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::FLIP) { - control_loss_count = 0; return; } // ensure we are flying if (ap.land_complete) { - control_loss_count = 0; parachute_check_state.angle_error_excessive = false; return; } @@ -198,7 +195,7 @@ void Copter::parachute_check() const float tilt_angle_limit = attitude_control->get_tilt_limit_rad() + radians(PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG); const float vel_z = -inertial_nav.get_velocity_z()*0.01f; // Convert cm/s to m/s and convert NEU to NED const float vel_z_error = -pos_control->get_vel_error_z()*0.01f; // Convert cm/s to m/s and convert NEU to NED - const float speed_z_excessive_limit_mps = MAX(fabsf(pos_control->get_speed_down()), fabsf(pos_control->get_speed_up()))*0.01f + 1.0f; + const float speed_z_excessive_limit_mps = MAX(fabsf(pos_control->get_max_speed_down()), fabsf(pos_control->get_max_speed_up()))*0.01f + 1.0f; // Start attitude error timer bool new_angle_error_excessive = angle_error > PARACHUTE_ANGLE_ERROR_EXCESSIVE_LIMIT_DEG; @@ -224,20 +221,20 @@ void Copter::parachute_check() bool vel_z_error_excessive_timeout = parachute_check_state.vel_z_error_excessive && (millis()-parachute_check_state.vel_z_error_excessive_begin_ms)*1e-3f > PARACHUTE_VERT_VEL_ERROR_EXCESSIVE_TIMEOUT_SEC; // Check for criterion: "Flight mode is STABILIZE *AND* throttle is zero *AND* downward velocity is greater than 5 m/s" - bool stabilize_throttle_cut = control_mode == STABILIZE && ap.throttle_zero && vel_z > 5.0f; + bool stabilize_throttle_cut = control_mode == Mode::Number::STABILIZE && ap.throttle_zero && vel_z > 5.0f; // Deploy the parachute if a criterion is met if (angle_error_excessive_timeout) { - Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_ANGLE_ERROR_EXCESSIVE_TIMEOUT); + AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_ANGLE_ERROR_EXCESSIVE_TIMEOUT); parachute_release(); } else if (tilt_angle_excessive) { - Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_TILT_ANGLE_EXCESSIVE); + AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TILT_ANGLE_EXCESSIVE); parachute_release(); } else if (vel_z_error_excessive_timeout) { - Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_VEL_Z_ERROR_EXCESSIVE_TIMEOUT); + AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_VEL_Z_ERROR_EXCESSIVE_TIMEOUT); parachute_release(); } else if (stabilize_throttle_cut) { - Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_STABILIZE_THROTTLE_CUT); + AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_STABILIZE_THROTTLE_CUT); parachute_release(); } diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 59fa329350..2f79bc3de5 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -164,7 +164,7 @@ void Copter::failsafe_ekf_event() break; case FS_EKF_ACTION_PARACHUTE: - Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_REASON_EKF_FAILSAFE); + AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_REASON_EKF_FAILSAFE); parachute_release(); break; From f374e56b0c85dd1b6f8b6ca937438f5dfad43a6c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 18:03:13 +1100 Subject: [PATCH 124/155] Copter: fixed max nav alt check --- ArduCopter/mode.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 3d291db2db..591374fd4f 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -26,6 +26,7 @@ Mode::Mode(void) : { }; float Mode::auto_takeoff_no_nav_alt_cm = 0; +float Mode::auto_takeoff_max_nav_alt_cm = 0; // return the static controller object corresponding to supplied mode Mode *Copter::mode_from_mode_num(const Mode::Number mode) From 5c8f464fbbe1da9f0ba7d4f20274c7934748552a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Feb 2020 18:03:33 +1100 Subject: [PATCH 125/155] Copter: fixed land if manual failsafe --- ArduCopter/events.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 2a89ee52eb..8cff47720f 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -393,6 +393,12 @@ void Copter::do_failsafe_action(Failsafe_Action action, ModeReason reason){ #else arming.disarm(); #endif + break; + case Failsafe_Action_LandIfManual: + if (!flightmode->is_autopilot()) { + set_mode_land_with_pause(ModeReason::BATTERY_FAILSAFE); + } + break; } } From 83766747af868d47b2f1cd79ec02601bbf406dcf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 19 Feb 2020 09:22:31 +1100 Subject: [PATCH 126/155] Copter: added rangefinder height interpolated using inertial alt this smooths rangefinder heights and allows for good estimated for precision landing even with loss of some rangefinder samples during landing --- ArduCopter/Copter.h | 6 ++++++ ArduCopter/mode.cpp | 4 +--- ArduCopter/sensors.cpp | 21 +++++++++++++++++++++ 3 files changed, 28 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 63c858e166..1dda868f94 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -279,6 +279,7 @@ class Copter : public AP_Vehicle { bool enabled:1; bool alt_healthy:1; // true if we can trust the altitude from the rangefinder int16_t alt_cm; // tilt compensated altitude (in cm) from rangefinder + float inertial_alt_cm; // inertial alt at time of last rangefinder sample uint32_t last_healthy_ms; LowPassFilterFloat alt_cm_filt; // altitude filter int16_t alt_cm_glitch_protected; // last glitch protected altitude @@ -286,6 +287,11 @@ class Copter : public AP_Vehicle { uint32_t glitch_cleared_ms; // system time glitch cleared } rangefinder_state, rangefinder_up_state; + /* + return rangefinder height interpolated using inertial altitude + */ + bool get_rangefinder_height_interpolated_cm(int32_t& ret); + class SurfaceTracking { public: // get desired climb rate (in cm/s) to achieve surface tracking diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 591374fd4f..ebe833eb9c 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -522,9 +522,7 @@ void Mode::make_safe_spool_down() int32_t Mode::get_alt_above_ground_cm(void) { int32_t alt_above_ground; - if (copter.rangefinder_alt_ok()) { - alt_above_ground = copter.rangefinder_state.alt_cm_filt.get(); - } else { + if (!copter.get_rangefinder_height_interpolated_cm(alt_above_ground)) { bool navigating = pos_control->is_active_xy(); if (!navigating || !copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, alt_above_ground)) { alt_above_ground = copter.current_loc.alt; diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 1982632c8d..b693025b62 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -54,6 +54,9 @@ void Copter::read_rangefinder(void) // tilt corrected but unfiltered, not glitch protected alt rf_state.alt_cm = tilt_correction * rangefinder.distance_cm_orient(rf_orient); + // remember inertial alt to allow us to interpolate rangefinder + rf_state.inertial_alt_cm = inertial_nav.get_altitude(); + // glitch handling. rangefinder readings more than RANGEFINDER_GLITCH_ALT_CM from the last good reading // are considered a glitch and glitch_count becomes non-zero // glitches clear after RANGEFINDER_GLITCH_NUM_SAMPLES samples in a row. @@ -120,6 +123,24 @@ bool Copter::rangefinder_up_ok() return (rangefinder_up_state.enabled && rangefinder_up_state.alt_healthy); } +/* + get inertially interpolated rangefinder height. Inertial height is + recorded whenever we update the rangefinder height, then we use the + difference between the inertial height at that time and the current + inertial height to give us interpolation of height from rangefinder + */ +bool Copter::get_rangefinder_height_interpolated_cm(int32_t& ret) +{ + if (!rangefinder_alt_ok()) { + return false; + } + ret = rangefinder_state.alt_cm_filt.get(); + float inertial_alt_cm = inertial_nav.get_altitude(); + ret += inertial_alt_cm - rangefinder_state.inertial_alt_cm; + return true; +} + + /* update RPM sensors */ From 3ec28e64c73e697e4cc411eda652c84042ff6515 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Wed, 19 Feb 2020 09:25:08 +1100 Subject: [PATCH 127/155] Copter: smoothly slow for precision landing --- ArduCopter/mode.cpp | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index ebe833eb9c..a97150b740 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -542,6 +542,9 @@ void Mode::land_run_vertical_control(bool pause_descent) // compute desired velocity const float precland_acceptable_error_high = 100.0f; + const float precland_slow_descent_speed = 40.0f; + const float precland_slowdown_height = 50.0f; + const float precland_commit_height = 35.0f; const float precland_acceptable_error = 15.0f; const float precland_min_descent_speed = 10.0f; @@ -558,13 +561,22 @@ void Mode::land_run_vertical_control(bool pause_descent) max_land_descent_velocity = MIN(max_land_descent_velocity, -abs(g.land_speed)); // Compute a vertical velocity demand such that the vehicle approaches g2.land_alt_low. Without the below constraint, this would cause the vehicle to hover at g2.land_alt_low. - cmb_rate = AC_AttitudeControl::sqrt_controller(MAX(g2.land_alt_low,100)-get_alt_above_ground_cm(), pos_control->get_pos_z_p().kP(), pos_control->get_accel_z()*0.25, G_Dt); + cmb_rate = AC_AttitudeControl::sqrt_controller(MAX(g2.land_alt_low,100)-get_alt_above_ground_cm(), pos_control->get_pos_z_p().kP(), pos_control->get_max_accel_z()*0.25, G_Dt); // 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 (doing_precision_landing && copter.rangefinder_alt_ok() && copter.rangefinder_state.alt_cm > 35.0f && copter.rangefinder_state.alt_cm < 80.0f) { - float max_descent_speed = abs(g.land_speed)*0.5f; + int32_t rangefinder_height_above_terrain_cm; + bool rangefinder_height_above_terrain_cm_valid = copter.get_rangefinder_height_interpolated_cm(rangefinder_height_above_terrain_cm); + if (doing_precision_landing && rangefinder_height_above_terrain_cm_valid) { + // Smoothly slow for precision landing + const float p_alt_hold = pos_control->get_pos_z_p().kP(); + cmb_rate = MAX(cmb_rate, AC_AttitudeControl::sqrt_controller(precland_slowdown_height-rangefinder_height_above_terrain_cm, p_alt_hold, pos_control->get_max_accel_z()*0.25f, G_Dt)); + cmb_rate = MIN(cmb_rate, -precland_slow_descent_speed); + } + + if (doing_precision_landing && rangefinder_height_above_terrain_cm_valid && rangefinder_height_above_terrain_cm > precland_commit_height && rangefinder_height_above_terrain_cm < precland_slowdown_height) { + float max_descent_speed = precland_slow_descent_speed; float land_slowdown = MAX(0.0f, pos_control->get_horizontal_error()*(max_descent_speed/precland_acceptable_error)); cmb_rate = MIN(-precland_min_descent_speed, -max_descent_speed+land_slowdown); } From 7cde50c71a11c4b88c3c1b9db81a8481378a5f96 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 27 Feb 2020 09:29:18 +1100 Subject: [PATCH 128/155] HAL_ChibiOS: updated MttrCubeBlack defaults for 4.0 --- .../hwdef/MttrCubeBlack/defaults.parm | 32 ++++++++++--------- 1 file changed, 17 insertions(+), 15 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index 2b8634de7a..6813d2c88e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -12,16 +12,18 @@ ATC_ANG_PIT_P 6 ATC_ANG_RLL_P 6 ATC_ANG_YAW_P 5 ATC_RAT_PIT_D 0.012 -ATC_RAT_PIT_FILT 6 +ATC_RAT_PIT_FLTD 6 +ATC_RAT_PIT_FLTT 6 ATC_RAT_PIT_IMAX 0.444 ATC_RAT_PIT_P 0.055 ATC_RAT_RLL_D 0.012 -ATC_RAT_RLL_FILT 6 +ATC_RAT_RLL_FLTD 6 +ATC_RAT_RLL_FLTT 6 ATC_RAT_RLL_I 0.1 ATC_RAT_RLL_IMAX 0.444 ATC_RAT_RLL_P 0.055 ATC_RAT_YAW_D 0 -ATC_RAT_YAW_FILT 1.617667 +ATC_RAT_YAW_FLTE 1.617667 ATC_RAT_YAW_I 0.088756 ATC_RAT_YAW_IMAX 0.222 ATC_RAT_YAW_P 0.4435 @@ -42,7 +44,7 @@ CAN_P1_DRIVER 1 CAN_P2_DRIVER 2 CAN_D2_UC_ESC_BM 0 CAN_D2_UC_SRV_BM 0 -CH7_OPT 0 +RC7_OPTION 0 CHUTE_ALT_MIN 0 CHUTE_DELAY_MS 500 CHUTE_ENABLED 1 @@ -160,16 +162,16 @@ RNGFND2_ADDR 112 RNGFND2_MAX_CM 700 RNGFND2_MIN_CM 20 RNGFND2_TYPE 0 -RNGFND_ADDR 102 -RNGFND_GNDCLEAR 15 -RNGFND_MAX_CM 12000 -RNGFND_MIN_CM 0 -RNGFND_POS_X -0.124 -RNGFND_POS_Y -0.097 -RNGFND_POS_Z 0.037 -RNGFND_SCALING 1 -RNGFND_STOP_PIN 55 -RNGFND_TYPE 0 +RNGFND1_ADDR 102 +RNGFND1_GNDCLEAR 15 +RNGFND1_MAX_CM 12000 +RNGFND1_MIN_CM 0 +RNGFND1_POS_X -0.124 +RNGFND1_POS_Y -0.097 +RNGFND1_POS_Z 0.037 +RNGFND1_SCALING 1 +RNGFND1_STOP_PIN 55 +RNGFND1_TYPE 0 SERIAL0_BAUD 115 SERIAL0_PROTOCOL 1 SERIAL1_BAUD 921 @@ -220,7 +222,7 @@ BATT_LOW_MAH 0 LOIT_ANG_MAX 20 PSC_ACCZ_D 0 PSC_ACCZ_FF 0 -PSC_ACCZ_FILT 20 +PSC_ACCZ_FLTE 20 PSC_ACCZ_I 0.5 PSC_ACCZ_IMAX 800 PSC_ACCZ_P 0.25 From 2567693ab9c4dcab7da55e69f40f231a6ebb5a48 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 27 Feb 2020 09:29:59 +1100 Subject: [PATCH 129/155] HAL_ChibiOS: added MttrCubeOrange build --- .../hwdef/MttrCubeOrange/defaults.parm | 258 ++++++++++++++++++ .../hwdef/MttrCubeOrange/hwdef.dat | 14 + 2 files changed, 272 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm new file mode 100644 index 0000000000..6813d2c88e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -0,0 +1,258 @@ +AHRS_EKF_TYPE 2 +AHRS_ORIENTATION 2 +AHRS_TRIM_X 0 +AHRS_TRIM_Y -0.0135 +ANGLE_MAX 2000 +ARMING_CHECK 16318 +ATC_ACCEL_P_MAX 36000 +ATC_ACCEL_R_MAX 36000 +ATC_ACCEL_Y_MAX 10000 +ATC_ANG_LIM_TC 3 +ATC_ANG_PIT_P 6 +ATC_ANG_RLL_P 6 +ATC_ANG_YAW_P 5 +ATC_RAT_PIT_D 0.012 +ATC_RAT_PIT_FLTD 6 +ATC_RAT_PIT_FLTT 6 +ATC_RAT_PIT_IMAX 0.444 +ATC_RAT_PIT_P 0.055 +ATC_RAT_RLL_D 0.012 +ATC_RAT_RLL_FLTD 6 +ATC_RAT_RLL_FLTT 6 +ATC_RAT_RLL_I 0.1 +ATC_RAT_RLL_IMAX 0.444 +ATC_RAT_RLL_P 0.055 +ATC_RAT_YAW_D 0 +ATC_RAT_YAW_FLTE 1.617667 +ATC_RAT_YAW_I 0.088756 +ATC_RAT_YAW_IMAX 0.222 +ATC_RAT_YAW_P 0.4435 +ATC_SLEW_YAW 1500 +ATC_THR_MIX_MAX 0.5 +ATC_THR_MIX_MIN 0.1 +BATT_CAPACITY 13000 +BATT_MONITOR 20 +BATT_VOLT_MULT 22.7 +BRD_SAFETYENABLE 0 +BRD_SAFETY_MASK 0 +BRD_SER1_RTSCTS 2 +BRD_SER2_RTSCTS 2 +CAN_D1_UC_ESC_BM 0 +CAN_D1_UC_SRV_BM 0 +CAN_P1_BITRATE 1000000 +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 2 +CAN_D2_UC_ESC_BM 0 +CAN_D2_UC_SRV_BM 0 +RC7_OPTION 0 +CHUTE_ALT_MIN 0 +CHUTE_DELAY_MS 500 +CHUTE_ENABLED 1 +CHUTE_TYPE 11 +COMPASS_DEV_ID 592905 +COMPASS_LEARN 2 +COMPASS_MOTCT 2 +COMPASS_MOT_X 2.38 +COMPASS_MOT_Y -0.67 +COMPASS_MOT_Z 1.93 +COMPASS_USE 1 +COMPASS_USE2 1 +COMPASS_USE3 0 +DISARM_DELAY 20 +EK2_ALT_M_NSE 3 +EK2_CHECK_SCALE 100 +EK2_ENABLE 1 +EK2_GBIAS_P_NSE 0.0004 +EK2_GPS_CHECK -1 +EK2_IMU_MASK 3 +EK2_MAGB_P_NSE 0.0001 +EK2_MAGE_P_NSE 0.001 +EK2_MAG_CAL 3 +EK2_RNG_USE_HGT -1 +FENCE_ENABLE 0 +FLTMODE1 0 +FLTMODE2 0 +FLTMODE3 0 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 9 +FRAME_CLASS 1 +FRAME_TYPE 1 +FS_GCS_ENABLE 0 +FS_THR_ENABLE 6 +FS_THR_VALUE 0 +GND_EFFECT_COMP 1 +GPS_HDOP_GOOD 175 +GPS_POS1_X 0.182 +GPS_POS1_Y -0.05 +GPS_POS1_Z -0.04 +GPS_SAVE_CFG 2 +GPS_TYPE 2 +INS_ACCEL_FILTER 20 +INS_FAST_SAMPLE 5 +INS_GYRO_FILTER 20 +INS_GYR_CAL 0 +INS_POS1_X -0.077 +INS_POS1_Y 0 +INS_POS1_Z -0.05 +INS_POS2_X -0.077 +INS_POS2_Y 0 +INS_POS2_Z -0.05 +INS_POS3_X -0.077 +INS_POS3_Y 0 +INS_POS3_Z -0.05 +INS_TRIM_OPTION 0 +INS_USE 1 +INS_USE2 1 +INS_USE3 1 +LAND_REPOSITION 0 +LAND_SPEED 50 +LAND_SPEED_HIGH 100 +LOG_DISARMED 0 +LOG_FILE_BUFSIZE 40 +LOG_FILE_DSRMROT 1 +LOG_REPLAY 0 +MIS_RESTART 0 +MOT_BAT_CURR_MAX 60 +MOT_BAT_CURR_TC 2 +MOT_BAT_POW_MAX 2000 +MOT_BAT_VOLT_MAX 50.8 +MOT_BAT_VOLT_MIN 35 +MOT_HOVER_LEARN 0 +MOT_PWM_MAX 1940 +MOT_PWM_MIN 1060 +MOT_SAFE_DISARM 0 +MOT_SPIN_ARM 0.11 +MOT_SPIN_MAX 1 +MOT_SPIN_MIN 0.15 +MOT_THST_EXPO 0.8 +PILOT_THR_BHV 0 +PILOT_TKOFF_ALT 150 +PLND_ACC_P_NSE 2 +PLND_CAM_POS_X 0.165 +PLND_CAM_POS_Y -0.014 +PLND_CAM_POS_Z 0.151 +PLND_ENABLED 1 +PLND_LAND_OFS_X 0 +PLND_LAND_OFS_Y -2.6 +PLND_TYPE 2 +PLND_YAW_ALIGN 18000 +PSC_ACC_XY_FILT 5 +RC1_DZ 30 +RC1_MAX 2000 +RC1_MIN 1002 +RC1_TRIM 1500 +RC2_DZ 30 +RC2_MAX 1999 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_DZ 30 +RC3_MAX 1998 +RC3_MIN 999 +RC3_TRIM 1500 +RC4_DZ 40 +RC4_MAX 1997 +RC4_MIN 1002 +RC4_TRIM 1500 +RCMAP_PITCH 2 +RCMAP_ROLL 1 +RCMAP_THROTTLE 3 +RCMAP_YAW 4 +RNGFND2_ADDR 112 +RNGFND2_MAX_CM 700 +RNGFND2_MIN_CM 20 +RNGFND2_TYPE 0 +RNGFND1_ADDR 102 +RNGFND1_GNDCLEAR 15 +RNGFND1_MAX_CM 12000 +RNGFND1_MIN_CM 0 +RNGFND1_POS_X -0.124 +RNGFND1_POS_Y -0.097 +RNGFND1_POS_Z 0.037 +RNGFND1_SCALING 1 +RNGFND1_STOP_PIN 55 +RNGFND1_TYPE 0 +SERIAL0_BAUD 115 +SERIAL0_PROTOCOL 1 +SERIAL1_BAUD 921 +SERIAL1_PROTOCOL 1 +SERIAL2_BAUD 57 +SERIAL2_PROTOCOL 5 +SERIAL3_BAUD 38 +SERIAL3_PROTOCOL 5 +SERIAL4_BAUD 115 +SERIAL4_PROTOCOL 100 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL -1 +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 34 +SERVO3_FUNCTION 36 +SERVO4_FUNCTION 35 +SYSID_MYGCS 255 +TERRAIN_ENABLE 0 +WPNAV_ACCEL 150 +WPNAV_ACCEL_Z 100 +WPNAV_RADIUS 200 +WPNAV_SPEED 1600 +WPNAV_SPEED_DN 400 +WPNAV_SPEED_UP 400 +COMPASS_ORIENT 35 +MOT_THST_HOVER 0.185 +ATC_RAT_PIT_I 0.1 +FS_EKF_ACTION 4 +COMPASS_PRIMARY 1 +FS_EKF_THRESH 0.8 +COMPASS_DEV_ID2 73475 +COMPASS_MOT2_X 1.87 +COMPASS_MOT2_Y 0.45 +COMPASS_MOT2_Z -1.05 +COMPASS_ORIENT2 36 +COMPASS_TYPEMASK 63423 +EK2_ALT_SOURCE 2 +GPS_AUTO_SWITCH 1 +GPS_POS2_X 0.182 +GPS_POS2_Y 0.05 +GPS_POS2_Z -0.04 +GPS_TYPE2 2 +INS_LOG_BAT_MASK 5 +BATT_AMP_PERVLT 45 +BATT_LOW_VOLT 36 +BATT_FS_LOW_ACT 0 +BATT_LOW_MAH 0 +LOIT_ANG_MAX 20 +PSC_ACCZ_D 0 +PSC_ACCZ_FF 0 +PSC_ACCZ_FLTE 20 +PSC_ACCZ_I 0.5 +PSC_ACCZ_IMAX 800 +PSC_ACCZ_P 0.25 +PSC_ANGLE_MAX 0 +PSC_POSXY_P 1.2 +PSC_POSZ_P 1 +PSC_VELXY_D 0.35 +PSC_VELXY_D_FILT 5 +PSC_VELXY_FILT 5 +PSC_VELXY_I 1.2 +PSC_VELXY_IMAX 1000 +PSC_VELXY_P 1.2 +PSC_VELZ_P 3.5 +BATT_CRT_VOLT 0 +PILOT_SPEED_UP 300 +ATC_INPUT_TC 0.0833 +LOIT_BRK_JERK 3400 +LOIT_ACC_MAX 350 +LOIT_SPEED 750 +BRD_SAFETYOPTION 0 +INS_LOG_BAT_OPT 1 +LOG_BITMASK 65535 +ARM_GPS_HACC 2 +ARM_GPS_VACC 2 +LOG_BACKEND_TYPE 1 +TOFF_ALT_CHANGE 2 +TOFF_BARO_DIP 2 +TOFF_HOV_PCT 80 +TOFF_POS_CHANGE 2 +WP_NAVALT_MAX 3 +ESC_CALIBRATION 9 +ADSB_ENABLE 1 +ADSB_LIST_RADIUS 10000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat new file mode 100644 index 0000000000..1b9d89b209 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat @@ -0,0 +1,14 @@ +# hw definition for Matternet CubeOrange build + +include ../CubeOrange/hwdef.dat + +define MODE_SMARTRTL_ENABLED DISABLED +define SPRAYER_ENABLED DISABLED +define GRIPPER_ENABLED DISABLED +define WINCH_ENABLED DISABLED + +# increase arming delay +define ARMING_DELAY_SEC 3.0f + +# log for 60s after disarm +define HAL_LOGGER_ARM_PERSIST 60 From 6313cd8f2ec24533ba72533be5af453859c03104 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Apr 2020 09:30:39 +1100 Subject: [PATCH 130/155] Tools: update MttrCubeOrange bootloader --- Tools/bootloaders/CubeOrange_bl.bin | Bin 17364 -> 17372 bytes Tools/bootloaders/CubeOrange_bl.elf | Bin 510524 -> 511120 bytes Tools/bootloaders/CubeOrange_bl.hex | 1700 +++++++++++------------ Tools/bootloaders/MttrCubeOrange_bl.bin | Bin 0 -> 17372 bytes 4 files changed, 850 insertions(+), 850 deletions(-) create mode 100755 Tools/bootloaders/MttrCubeOrange_bl.bin diff --git a/Tools/bootloaders/CubeOrange_bl.bin b/Tools/bootloaders/CubeOrange_bl.bin index b54d6fd2cbe599b35941504239af5d34fe7859ed..022f275dca1a4f46a10da7f3b4e88b3c4a07d299 100755 GIT binary patch delta 6838 zcmZ8m3wTpiw%+@kljI}~ZQ4>u(?U;@0%_Bh^Z^DakS5{u5ugaD3=cVJMbbKI#K+Xf zOv_6P>R8wvMXC-`Q64@hTD2p!*y1?exz25XdZCPhqEl@3dIH6qrfqW9Y3tRw{l1;` z@7G#;t-a3LYww)HPJ=xay;6lVsTZGtB zC=Wt;dC!aa__IAPy6~JmUy&(al7o zZN)L3w#MqEnJVGDeATh&*-g03BPtWHPVCIw>m!QvYL-{QHoH2XWTh@4Xts433l(fg73 zI})#ajP_)gk_M$E)AiHkKXhLIRM~lbdER@fm6+;}W$k<}kLQ*2BP|L#94*1<;x6fd zPV%+#_F9A}mi+-;Mo@rr`SZu$UdoxGM%HEd@(Ip{KF_RA01o$Yq0tSP?P&`Q)0^@58iJOkolFe=2HCU=lN8A8o!TE^m_zq zFXoWgJd9=|F@bcbtSn`W0V`+O$TgK+$rv3{!9rqVO&X>Ei3h`sF{Xj6XEQgKiwJb) zK;xT+H->kGSHRx=F|6X(w5;IOL99mNb75o&2D11gJepPMd9Dwe7x5Hlh8d~D7bVvA zl2duc2D3JWv27s0%pL4QGpVK{d=@|5e-ppbbGv}Vh2#e|mF1`=*|Z@Nub#>(2Q)NH z=ZH<6&M-}dWn_&yHA{DFrbwgw($!1!ZcE2%-UN(0!X`dy%qcA|6B=;@K0U`rxl^S@B`;=#-}QP$$YS#SP| z@4gsQ!fiYjzYNFhLt;`GiT^c3H!bp8!|aHV7xQO9R0#NL3i ziA8J+(4Wf?)W6d}T@7D6&_|&hk?Sz#qY1ho2C;n;^J)PfcpRhb@2(ev+dqiXsW+3# zm$)uTYwDB|UiRD&O0jJW?-*K}io2Vg34t|II>M%0p7x!UxC3ObHodkYTrNg!*ZNQg z0$ZJgk7G614cvE(qY}RM#PVgpaYY?)`xP_Y7&GSom|6MmV#cBfs6B|=E}@3@tKt*5 zfXccOC?5>_v6wR^M{fPK92M`ey<@0Rc~(g#hlaJayMegcKfwPvJ?aX)u4zb*aPLdZp zUx^pS@LD(75<4$Wht@M-A)Tk_8piAD$;nv9WH*?~UyRVt1>#RD(Zv}|Yg)(E``y!Rm;eSx*WzS)LDtBE0|QY{Knn0ecx9ZRaq6uBsV@Oxm@Jvk`9OHKwcHl z!8*Sj&Z41nWJCPag@22Vhc_6dz9bz!0P!ehvdFP{fd$H>p7GYk1DrChXBW(pqf>AQ zS!}&57Y!XHE%8OQcYh%F9D8a7|EzR}E*aEcAAS;AzOOpjS9ij)vwjSB^vx0-Djm$a zFFITJZ}4*2AT>}DTXjoi)6WVs!N~|UB6Im5+M+E*;#G+W+Mz|Rt37IH@eZjyTH{LY z$|lxhzLPrMepMF>0&jm`X7)OiAIR?$k{N8>dMDYRusY#pg-gVAv)~+j_I??eg}sUC zwKd=@@&x3j)}Wx^LSh=F#tt=o!|VF=L>+>!CJ~#V$3YzEhSzaQs>`JXf3eh>#BcL4 zd<=ioiO%fwy<9c3>LEj`Q*}nqXTsinGTK~abvJt_U5>x-R!SZ(?`QkyeEut+%^eNB zKl-(AzWboJxz=al*QGQIQv3L{*GI4TzUkZUBTo4gWcWBfiI>?6z<%x+`%Hcwu-Z3T z3G6Gqv6mAs92!uvd1I|lk2?9bq$qV zQyaiXnBY=`#fIoPsnJdGxXJi12d8TP5OrMFKG}xF#14cYnB~iO65ypkzny54@g=}= z-&Y@wjmwqsMZj`j%lNoF86N}OEj6awTN7vc6nt_GlYzT2XK%-kQ5oSt!o!$bzpKH) zI0gd>@Et7PPgwJ4n~H3 z>#9qZ-=FPkN8l`PEY^@#izx56Xmyd~ep=~F}@m^n}w8OT{=jx}-jnZ}<$(xqL(#9Rq zlLE-`O|xfne7sl}hs8J?+l|FLC2Uc4Qu z?**JhZUC0T>i~a8rcGa^z6u}eWhmc}ho|4K;CKU{OoG!>)V~jp>u@(oO1n$#nyBTI zU1>9zZ9eej6KQM4K`fV^zDh6%dM`H94@5$z+g^ub%adwrRq#(7*DTd_o2&3)bs4#p z%h57?k=I(a)wkcb$4MHvGJ3UOB42PzCN~H5$R+8rC=)HQSqOerS!Ay9aYoPo#!F5a z-3BVd;8F6Og1v(>uCLa6415~DQkuN+Pfjx3G^OC;U-Z?-eCY;lGIjPFL$;5({DPA@ z!$G$2W%!uy1?S-TyL@wm`-SO(998ZS-Vu&~EltjOh}-Y1@U9a6CeQ)6$at{$@?VIr z-bcH+Y9gr0R#qn%h_mm)^MRS#?%$rV%4Ehphv_CraBY{K8V|G1K8!SV4M z8E_i?NwV;fP-OJf30LYm^!QahGW%&WRlrEN5Sf$t-V;7Z7bGwJ*#si6)^ zLwflosqp}m<2f~a+f0A^Rp}WyvjJL;#n$#2IXMB9sR%ydNGN^O-*!<#Hq{(Wfm_lP zUW7ZLTT&K&0GEn%i7Nb}k2RI@mZdN>ZggMU!PHn!qJ-0^Jhgh&l212K5|f%-Bm1$8 z=~OYGFJR|%_09C-Ik=#s@1GM&{s=VM7fg$}8ch3!ES!-$nd#A#tre(XecoE(tfV!b zQ7L=Kwi#IobWg9(DLSZLXx155suVqMpPIqqS|!{}_wW~$Wq~F9CF%I_Xvh&gGN7Pc z?ldcNJ{npV#hk3EGFanEE8|Ltlk;$8`#SdXbZ~@DD}TIWFF4#9u-TNT>_LiPD)s7s zB9;~w_~egwfnZJRm5^hys9?f@RT7g%oXaIzHyG%+Uj9tf5E_oi(>PNGoGLbcflp5R z76@2eMZB|8G&&Bg)EUuAEk_=om7}5D%si#%%n8UqKb(~}U9OsaXHK}_bTJF8r@@H= zwsv>w%@VT_oglH6`AWnUNz5{`+%lKJCdxzVEx*N=$PLQ|3tW63f{QOBUwjXZU3`_X z7T(A&??);;PrmqeNy3)$RPsp1a_+nfvBDh0{aoPav>}tNHJf`Rr3M=dzl}C_tnDol$efy)?nLbI zJV?3_uSPf<(MGHy;D9?)1y67qYm;-5hpz3gB`Y=1_PXyQZ2-vH5WU`Ygso_$VtLk7Ud)! z4Lr^gOLlrKGAV*OEi({HcS$@M4_2(F>$yVl{aS77rwU_pnq*Ard9%>Jqy znaisFA?fBRf{SUCxu9FKn;F6Ek^ysNObvriKkqrB;5k5kA@a( zCD(H1Cn$I=uN){!JS(w}&R2E8FIhBuo30G|TfdN<$M)N*nZADsq<{lhE4(TfbkW=$5Ix*pGqsz#WX^&5&?>3@8$^jpi$;9@z`ih&6W! zGjyWKM;^#E;Q{ho?(Et(B1dVu2gB(e4ZRk*3otc?UyjTMOpoEF$W@B&VaD*EB1Zr# z#_%(dYQV}dyenb_tQy1HBR^ughaJPekN9av@RPdlRCJGg{zgM=^eEtQiBxU$E~t!) z9Er>ZJTCI5$p0vR7AZy!10EOIAE^R7F7lg5Cg5?AUq%KLj$mUQ$Fq>lh{e%R&xhwA z@`F>e;K&+CF5z*YKGfvHo%QPW@u2eKRgpUNLm-6oPG8N8>trZ_txGHUsZy{4rb*E6|#ol{GjJH*E zRzyP2lRX6~MabCc!+D)TXH}wmTNQEA-t-PvHSLXrwtOh(u#@;Jz6C86Rd7|Dmf&ly zNOWJRu(z8Z$#0WSwn(U){7^8BAx@W<#Llq;Xs#e-b4qN72NW?^s@EBsmRLHP_z!}P zxReX|JPtZ22)!|ToRFZ#3GYVYTgOy&RgR^V)v|h>g0osS0y2#&dYUYlo8|&V zt8jjo;F?g>HKwQw6m0?n{i3QFR5eUHSn)NC`*&4;M_!zp1{%_kR?U4p^T>db?yFvG z_%l4urtyy1DHjw$2YrjgSYLEH;CDhhSvUVpGqvvwH&-uoFLEyc-N?b4AP_jI30uS6 zq5_-0?L*>I&tCiVxRb+?(3c~1rm3Z}hg;#qQeSNraE-_mVdndu^Za6zmv+RFO_}tl2p^MsS2+8stfRVJhS?! z@1>MyovCNxsX=qpXRhv%w8!5yB)ZKNR`B4BLZ$a(Nn3{l(a@7o`6N#@Hyf^V3WZL}M>d(T_(63Qf(O|AGv4ma)~T`w(=8`+Oxj`&W60+3S`>v zU0c~JtQD|nt=AxohAbz?-VoqLN;Z znrGOIOoq({NS82W5LS>U3XQcTWxW+8Wd<*_$|D30knl->%N>*19KAs-&^DABU=M9{KvC{SWD z8TWh32kR?(y$+KBY=Tzy-jQ2o*pyqgb`urcqOPEB+~?fCX?7V&U)ZWbSci0%5xKl@ zCSF4}E=nS)i>6@b7%Bmj1;~o0jMWc79g+7IZNi_CX^S7cYwyWAgw~vb=Q5>{ZDsk< z&<8_Gqlz01y$6&9`ZiEC(6@kUfF1)n73ga~EszYdj?vJ|aHnKjqoGGfM??2XqaoMu zXeb5n55v*W>`{44H1y-!ql@ptxQ0{}dGKk{TC_cWJ@~6He>{!C5V(>_sk4}er>WIY zK}X?F#?h!;oA`6+#=y~|yN@Ek|JJvan&>-v6cv%ro$qG-JaawV5*9<}3I?Ig6Bs=! Uk7nWjQwW`h%$eNhn2OQ=0$i~$=>Px# delta 7008 zcmZ8m4SZ8Ywx7B8Cb>xqO+SD%ZRt(Y*7SoC+JfObO~Ng03Pr%R3o19Q$W3*%i?|D} zYm0zFb=TssECTMLU0lA@w%Vr%HPC{q``g{u0QF(j1x2^mx_TqU+@@{v&P~hHee^du z|CxK{%$zf4&YT%Oc^Y4O8qYus;$ETl1m zosYHTH}o{zOb*j`VvdZ^mWGNku5Gd}Eg6<_+@&JxCtvr!h}C`lTg)P|(DWF+k#L(;EDIUY&%!$^8f9_~k3|L$k_!G7dl z3cMI;TGQc5-)1mTErnH@}>Se};k07aRly1F8W=3q}D3hz(BWKxE z{7!xvPd;I|IWx!p8e~3NvHP+S*9>^Z zS5oO}&z zou9?yxl0F7d|NQOxLe-Tg@O(T`KS8c2KL|RDnb;CfP(a@7h2z_#Lb*JYSJHhMMP3` zq_rY>a|_>c^7WcE}|Q851dB z%{nBtgqf1KW~f%Pd5b8H18wJzR7ps?F1#ze0#@|5VGUp1rl1$X+91{gK~HE>L~F5L88Ub&4Y2es8KlI|VR1sNR~)fVLacx{Uuh^>S* zUIC>9@E)LsBgmo{8b8urLiup4-BnIdgmlA2%ULRlc~ zN5b?I!k7tR`Fu|qV^syTo^3K}MqKB0>1kX-6cA7b%!LPaW^Z3*&h5;N-c9 zexyftGhjWvXYJ0??=U8BPIj!egBf8K=vL8pAPaHQJ%79V+-h7r+z+7%**e_QQ-*Ou z951wyVYFh069+L?2aG47#x)vkop|0i{U|RK(DOFnC+>tr4LPH^U>+nbADtm4FYT3^ zxeGF5cS#i81r$qP$dk*h%J(tlTl`YxYkaw7;`ti8S z9VdTIEN!^|l=A8LvwP+H^egyOu-aYWXQ1V4-|7CwcI%FvG3@WxbGJzjO*FJII#c+c ze#MHLp(J$$dG>#^J)Z(7Mw zt)18P4wNh1`?ezN1e9S&Bu-cnhc+Vz`s}7E+k6>1c7B`{~+M&$>TQ?cq^g6JGIL^q8 zvuL5dOzxP%KPjqx$DDEeR-fI!L;QuY!^!ZP3kEo!qoKcywfOSgE#6626F(~A4bbxL z*z0NY_|HU}I~sa>>~nFR`(U6=XkdhW7otl`nQS7Y0U7%Ifc)O33vGB zfcOMneL)fa!dNW`uLa>rApG#4nvI5@8*}m}Q?H8AP!kAux@){G6S5(?Y*l(a5tFU& z(791ow-?SU!66WH%G=mMK2C8l-QGkuF;96Le?vZ=(tCjSrZ%P&_9hX<(RY)pw>qkbyXWAeI&@ zI1X?n&}$QI3jP$Z^6kpIF}_&}{s^%0?e%fKA_X4>+#~PFvUeosh^d>ITosRdFlXG`py$1*DzB}Z#pCINg?+d3=Efnv&mzI z%DBEUg)jS;FhvqDY_KQ7+!)>%Q06r)khOeu2&RA zK^ujFE3i{$<~KPndcy&Ft7~h0nZ1MI$G1PqE(NZ5TH$ob%v$0c2`KU%GG(#U?}$l- z@Z5n0x6&$pg|APT%%|{%HoX~{q75N$_>ga+5?ULc#akiH)jP0Md=epg7Y$nr28>bH z*73>cX=H+d(v*R)^cL_*Z-Q{9Y}Xee&i<3{H;#p_C0i}9PA?0!f^-^77ypk(6XUrr z#-jqBnje@v??7&8(RV0%GyEZWr>#+Lg7S<_(HJxYJJ=@dFcR1<*V_~=H_5ePnrH#b zB9jtD3}woJ;}WUOX=0=NET=M)$J6ZiVbYQ2(yB(0N$GTx;Pkh&+d;fi%Oq#h7nam+ zpe!vLzTD8%zej%3hVvVS>R*2oCZQZS{{?M3IIp-z-fmk4zuWY#0m{Phq$s11-7Y^P zq=~eNh#B@7iBe;NA~OL`?!nT1GPbIFC~Lz|`s;^zeq-ek_%dzh{^< z=8=a1CzG3izYnhk+)py5uhM=38}$;D%Vf*+M^r{WmFGxsdYblE;c*=vAX73Q(3Vcr zW|3W)*$lnuNs+W?R*!?pTvnD*SS1*|;7pq$p>roszyWCM@T5Q8s^WE(`W}l zO>U#n(4tOccrgIPhB@4OFeC=1;?XGQu)62W+xM*7<}0Xabnjo zAlYJhWa?E|6$T_L>4d!_ep!6wr1CtTP+3JYY|y+AiU&$P>`<1U1Oq)e_Fg+UMG3t* z?xcaQ?<|68L_+I`H)~46gJb#S@3mVY23(1;iSt~$WaLPZ zR7^OqN@g;b%e0<2hXVc^RnJ93BavIZltgj9z?pM-8|>GrQLZf-N{=cDz5ExC18Dw+s+#-vx^viSnP zMrQn7GHN{;WD>};d3kXQ{E%coau*4mB4_iG7qvw-o^x`uO%1<$Y>*ZdAr3*>WpE<4 zHHH~S7GQca&adxK@%IGEJ<1gKIe!``^N^|e_T`gJ>$ylMIAZr)6YL-c*^vc)7oD+K z1jy%wsv#!1rMB3I@<;oyrPvE=AYG0W`##o;UP=Od0kHB7<-7vf7TK3yLVEI7Gm}lr zIFeORXjV?uoM^ASM-O?Zgp-~V&w=`o6yJYNPPc*+*vO`WIoL^#7u-P&m6Aw-RgDIp zVkhyWU`AF0GdLOU=-skDzsaWx>f=$Kv!|j-6|AP$;(4ymS76H}5JQLKZzQ{3aaZ_2 zC@Am`SwB}5Tuh_9`8~R(UC%tv;@qA73RjQ3PtOc)qkm#39iW_N<a8s8`p`W0LWfZYnKSv9-C#xUy~PS&1`rra*U>XF`W3((2>XkfTg!Fg?ENdIio{&ysjNAOTH+hT=LhVLi`~aF0$Z8 zl2PoM!uoZhCV!uws;7gPKIl)~`2_lujR(g*QIrkEL_v%9^_0lF5MRB-DcVoCbXO1;?IB|KTvRr9cfaU^sA zQhwU!^ub#|pi9)XDQ^;njQTR#mnw9LxTs6$@+G^U^wD18%<{YHXfHBFLYv-I65C1q zHF17hjW0PPNo=V}c3-Q3leW|HSn)~4?<1i*NU$V>aY0X#G~3R!)BspMd#U8+-~P^pry`H?3mM1}jJDLRb>Hi5skz794~`14Jf;#o!kD_f zkc8KC*U+FC6T3{E6P#YkyVc9oIBQ(BN@7XXbqUTor4^Zf(DgmCcuuCP%ZH1*1y@Wf zWp0XAu9#LYLeC%cviOV{FV}nyeE(msE###+nT%o)a&FF3>i)W;gKC%YFKv~`7bFsB*b>* zT?5f!m84KTx_ak7PMo(x`;4#Ts?5qOa%1y)A3OwT6gT|{UbS=Tj){Lr+w07@2(J^m zW1^+5SB`H@c3W!l#Z%68!YhN6y4HJMj&H<}3^YZR#|EqKa#<75^}gfcADmxM7y3xl zp2B$Q0ISOhB;#0bnp6R`Sr;F0Ni2P_R_CcT@2`Q=qNuM1nfH6w z)b%ul9x7HTTV}Fhc38QKTMOX%uW8qew~CmF+?6y5WEp zi~yeFHG)yl%D($-<+cjr`k$`fzkX(g$po@V@xpeE{wji7te$+mFbCgF7B8AYtc#{% z9#B5E#p;bvH^$HjKn&?#v>pdY?&3!q_MUD;sQL^%%c)Il2g{Fz&JU|i8Zh-)pe)c% zpjx0Of$D&E0G$T34X73JH`Xy0Iu18Zwj&zaIyM&iwLBIo9~ldo0N)sihGvf`Jn-~! zO7V3(mvT2daR8n*JM}VtBg1hQ#t)K5OFj5)a<+6^;tFtTv3NY|!l2g_a;LM52rhdn zYNVi!&@uQ2TM9*^v1+}Bl)COxIG}L3X{Sbz4!M#@8@~{e4pWSa=NO!tGcVJ ztE=nuIqX{ehmNci{`jA%i70kBiNUZEykan&ra@$ zNiu7uG+g&N@3-K-ng8{A{)r@(;M3Y)GldP%Or^MH<9haqr&tF27=H^{))U{dRXx7S z_-j3))7?jUF;>Pu%#dF*cKC@rW|A8@o5hT>yI|$aDr*HxU>@=j!2;M?`Mh8wScJSL zn01WphGnOhHD*TrjLkECn891FUoqHtOWIYV?dV=}`G$g^qby@XLH_T{GJOvkZCW&o z(JZ{>(v@yIwU#&RTFb*Xw3fTCTWng(^ebA+EA}hrwCG>X8EhBN$-50KFvwW$x;tbU zk7Qe3u^Upgmg4JT$9TKpTCRM>za=`BSayVe&?y!z0!w^~i!GTX=sycf4?R&!b9 z<-6|mDq$@HQ5Vhrcx^+^GdB1jWI7X)4sF~KH2P=^tQ9iOX>8F-_dBVst-MFQ^ zJg`Y?nJax<*xjN$sZ_3XVR7+=f1X)*_|k_ihc69D-{V@%_ysRhjxEi``jlMIJhj%m zyq&Eb1CQ8e9hTp@unEnY#!aSQv@;qmP_KM)$7>aqsE$as(!Aw`2Ce1VwH;-fZGQ7M z?`4s%miROssj*m>Uh-LXq`_k+Ygu?hvu;&gcoALb2Z-|6dcU2|m$P-jHJbIgvdyLJ znI~u$q>9JCdGqL!|l`R^&Zb8R;Uz>RK!K*_tkSngb+D7jjYIAF4Zd!}Hs>QV) zOSHXY(|S%Sm*<#ufQ?(Ms1bVY3%e=x=>nHeQ&Fq_Doee1%#eNgoEFR1zhq0ag*WxK zRhLhw(OUY;Ura32WZ~;c#BI{YjRlxoF1ia4u*g(57Hu%B&n=Uq-B@U%`Q_Lap=Fc~ z9~4*=cW}5Z3d9dyjk0w_CYNX}-(9V|u+=@GG!=@m{CBz0jg2r2gGKp{vay!0 zuX?Q2TDo7=TK;)Otd}2ou*BxYR}AYT`}rme{PWZ+Y*V$}+M*r&*i|$Afveu6nReo? zUsnMCEKX-Pj_D#l!x4WsmG_sT(q-`Gbl zaYYV-f7ST;Gia1w6P9#=1PX!B`$LZ+-C6 z0{*$Vh_!^ve<0I4;CkHNxCTqn{_{C`tR+fb>c(OMt>rDdtrZ~+J(nH1FP7(D1c@~jYnpz+IPI2Z zZx$RidgrPu+EA8uUxCZ9;Jrv&76qs7XMKM=r^UA&Guu-4%c0(EKy%{tUN*9=bb z_?4Wrue5w>H{=wyaB&!S)^fq_RT@Y6Hz?1ugmOJgHx^i(B`Pm}o8eI-j#96*mPv2r z?Eg7lvt;ILrn~}gt%mNgn&ml+Zq9Cxa-%JHp1VWju=}1z-7Mu=WMEXFt)uO^4r2{N zQyhc_f{+>knPg^RtWK7jSx+`Z&NO3@$&t^PS%|^C$aSzhU}njNf|^AMvc=3YyX6o0 z4WEbw&b~*QSHu-l$w7*?@2QAaQW>vSI`*r zylQCm*R<7|weqqy!?RRtId3<#<^V&mTe%xBwO8EAJtM0v-`AVUt+(+V`_G%bz;MEw zL~I+bU*tW$EXcqT7T+e<`Lf}@RmQ>=CN|d;TwXJiQr4O^ewcpqpgL4XE8?TI)|x`C zC4#%LJU8)2ZQ+Nz7HODDe$0xTyj6MHAGLXh?2FPwO;fRbcX!*827}GRwzWX}^uC5? z8)F;i1n(|z{WQ=Pk8yne#^%O^qRqA4&iH)3JtW;mW4r%GU)#40sYM-aZ{GN>p>NTq z+Re=kakjA`n``X*9o4qo_`c!nxup%O3TVAF*t~7sZA88X$WN;E zI^*~G^A}xA=?eSEjRM==pfe2}ZOg!*ps22Pvy(pN{bEPW1>o@AIZZR~b}!PRWw1Xx z#B${q{;bg8Q*@+OMs;UzvJ3Ky?rbwVA)9-!?mjCaBlB*H)nId|%y07f9&Bx zP@Z3b=P~w@p|wI|Eh{@t*jE>E8(SYa-+~qR!WF*5yx%{SwfG&>G}yTeN_RuL0{0)B zI7)wmH06DJK$T0Q^cP4|-cCokbV|RB^ilij=$zetu?Mu%?%7Y0Z%u&vL#JyjE3S zUNlo%!&B-@c8luRf(C4X3ArMY;uml=7R>hV!;%%-F?uI^iBfm8 z-;|wf3S#jg6`37vo7%56jBN~Q@Y`uYnNjWRCAtriyMr(Q#WyTag&pw4Xk2pkllfyU z1#gnRrgE)yC=*SZwXmkZZs@nX;CSuTV`6dP;-=!9-3FV(71Cm~R!>2t^J@z2hOw&( zt{o!=1$J(=Hr=PF!mRGrE-n^E+t5ZYo4@UJP2f&*lor|1+&1>=#zrU5HsWfUEe>X@ zDUY>e?bS5#plU>@#oo(n}_*~xqG@?x1%|e6!24@hx_C&8!nR&NpGT1chM*FhVMfT;m z9!jO2JLGWf*uD0qRO;m%`=o}D1}j9XMZ$pO1s213)%d)^hDG*=Eyk#j26=Y~%VBrQ z-65>d&Got#N!8jU3uSxUEVg?=o3%vBw?kR~%pWFCn#`@6Coey@+P)-}B{W}d+WtBk zKx@bwz};uD*lHVA+wV;s+)#LdTUXncnq_(zOE!tfd+iU^fLTKr%Sp1>d|DQHvlegW zb(FQ-W@m9OM|oWH<zz+8c^HFOf+u~LxM_O32r@@wA zo6xwpVO_&x1#+c@m5JdsQSvJb8|1&aHBc+Gn-h7Iu$vM!{B=!~*^%siL!j-JT6rjv z6$SHN!R0Qt!!?hz|A);>XVhCp8$( zY$)KLTHs=Qef8yr4F#7^-QJK@GqWbVhAhssn%8Syf^4H$K_AVsuAr`VSj`7D;uv;D z<*en|zpZLm)*y;3Q&!cumQ_#j4PI4n?(-*uRc^1f2Ump#g6?YheH6a5Z7- znrz*`>h2rw?SeLDig_M;18q(F(`~(g9V=_2S@-7KZX}kzw<`|T;hPTAPLciRu3m6o zI@(SFG6R~F-0jpi_LYlpt&Fbx#=d$Zt{utqYXUtptIWOvDZ3%iqOJJ0>gsY*E{S1@zT)KRhJuznej0dlWVNgD^pXJwB>cYbkQgZiy{&Xr#jlkb}$Qd)}?h`VMLjwWL1Hs z+)}po;5wUVy)Ggu??3oBG;cJ-)}wDNr*UY*Yf;ZjE1Yn zhS?1fs|tqLh57QagO@5F?FeqW)=t$dQN6J6q}uv5kh9pYhP4cnwLMvgyV;^unji{H?3saZIv(8yfgiA&Yvj0i7VP_^?FDQg z$Jh-A_qH0m58JgJa#=i!kLY_4?g*T}_O`tpZsqUTSEicqcXg^s;kL_T@hl)dx!u9$IUyIgq6lu!SV&iNt)X3Ed zEYsi>IoKjUNMOUIC6OgZ!9%`{*5BxkllIkSIIAtp_t6H7cKShlTB**|k0_%6eHV%L!0_C0+Ps<6)0 zc$Dtc=67*FiEW+5W`(QrE>i7nsW&o={3PjRgiJ_dgA7-8t#6RC(pVI`C}kQ;X?~@B zs}Ls{9D|Ow7u#<~nyd7)?I}nLm0sU|o{N(Pm42fAC8Uii{b>6Xq+L|{!S)2CT~&H% z`)^E~G^zAG?M))D_5DRZxr&ptVt2HeI<_M1;K-XhZU^9CdA&UaX$Q+c+kbV@S+=xq zLE6FcLVF|94wh%z1= zu(W8mbG|LYTRUcISTl&XGQQ;C!*)&6+&x>F=a1*W_5n?k?_{v$g@z2Vfz8k&4cA1> zky^ugtwu~TuFtD^yQZL)*WOoas4J*jT=#Ze;iOb}Y+6+Ql*2XowXAk}3u8;_4%fA} zJt-f{WFh%lvHy6@5b3Lvc+dL&NJ1;9Q1GNrkv8YjxT;DupLeco5u|=Ef z&Yh!e7~f#XU^9-?ife{Q&8pQbtvgaD&{r|Zu>Kv@-^HrGg_D$bI)(apxTatVNkWTq z^!6RuFPlXaqPLAK<48@Rv$ut+w}t5KdWh*}f34_maM-50?@;cq{hceH0wMHLz!}SC z_s73<(M6n_GBEfVM2I77c_|^E8(Z_l2)iNSse(NGb@q_@*VLQEdcJ;b^OXKY1B&{g ze{xfAmYTe-fIEebeM%j({%}rf8M;@LYf+;o1=sSZ)7VWT_~ohPX;G|vO%4n9-gm9N z?d$7{q5?{33?|8>99G#pexG*m1l*%sn0^ZRYT~M~h3;nU%!p66y;}r)(ogov@Cs7e zZ|w6{);A)M;QBdY*s)W#Has1&rXch~}K+C6u?5$soFtxJGPPpp|#`>x${ z5j)n=_D}}}D&iVX6)(rVzVYRTrwe}g^b2_-hef!|IY=IZjPAqo-1C0#xHF;TxP6&L zPV2*7Ww*+(zAVM<6$S$ENV<`aLtXjxP2-}fe080%f7p+ zT#G(#Uu2>3M{t*a_QhVfMZVvU^-^p95v=`3E)B_e-gPV!7yf6%4^> z)u(SwD+{hqD;rbKTW7e{@jvb?SXZA?CZqea-L4ulYvwbWJky`Wve9zl0M=cG4q!c4 zfg@c)=|oB=upSQ7MnY+F&j41>K9*qv+3edN-?vE9Mjt|~&Lz^c+hn`Z_SO}bNLR~^ zwmrC;aDNSVH{7@5?vDG*xCh|=BJOeUDNT7d+MdO})wH{#ZNZHjZFkylv=v^v(H4UA zFV{NSQf^S0j<(@$EKZfTd%mZ3{iU)dP@Cu@4Fy2K#u?zlG zZd4f8908!iAS-_|q(+`VwjpsTk@_5eL@7!dQlB9BCxV&W_>-Y~fE8$C0wk{qe^fUn zt4uE$8Owt`OTg46vm7FIeOP{TyD@-`krQKizg}O0xJ#d{$nY@a;jb`J$w6;X$&W$N z(xwzS?Si2{YO$VtJWG)id-4jeaFjK>ma^X=}dw##38^5yJ9IX{jk z@GMXHLL9%t%LXjZWl8pnA($1(`+MB^M;L?Tjs%_-SB>_1L>kVb_oi-B z-2g-xmH-Is=1b(P1|nzamL=U1`6mfW374U8aUyUTL756l6oHQrl%=3l5%{>|NxV0E zO7>0SFR)wWw@G{nOW$*AGT*`wAnBIM>x1m5;T6E9dO(C*z|(u*3M5?%J>^5G{BJCC zk1dU##^NO-Gk7_3mv?0F0MkfR@*TFxOHQ9{43L{McqqF=9?IYoS)jCJ^3kkb&d=oi zVg%&uU#nVg8tRF39i^i+@h3R>Ppa}(TJU)$xA>NWWcSbAFeN+;pA!Cd>5;{AygmR4 z7Uc?|a7{cUtFri@m;{vVvG5%)&@gQR!5$0$iFA%>4dmEk;U7MlHqJCr-g8uh$x~T; zC=d6P@!7lpzRn%l{3q!1sNOu*D-orGK4B%@G;LP5c==Fop2wb$ANA%lyf%ZWAu7TI zZPa>fkQF&RFyd9NJ>oL}j39{!s_y(j1<^Ufr{uZp<#9Iw7nO z`P(N%fz0pAN3cib!FPC|e-+3C7ngU}v~WvsMO+UI`H#|jG!I~3%co9?5=bz*A0Na* zWa4MS>Xihk1=o|*LQOHAa{Omv0tVq~Kc3Fc%A{PL=aqsM1vgU(e?!b6xgeJZ_3TSb z?j>BFA!ZT*_fHIhMjB!pCTYPB+={ejj2S53%H^?as{D>_FG{!m(BlR2&i;V><=Xyy z0GqJqU;Vi+V@Kt-&qdFWUrA)H><83$=@Ew&PA7PW_>47}M z>o<&2P!lT-LCd=Jl_7b27T@41AIsw>#!Ns167L5!_6^PUJ8>ml!9bi2)wE;)S^=)a z>F65!l?vQT;3E8SfUhByVuJV`VB)J7DM#`nc`%>HG|!@<8)k%QTD&_IlkHHcpMgwm zs=ZZXYw<`*>jv`>{}BGLCods48L7mR5I0*-94iS_4N%}B0v8cg1-?k&Pu0mi~)C2oOe*?4MZu{>75!<)lMQZTcS3GxamF2)PACJAre!UrPUoM%5sg5AYy-C3tSB)T z>1C>b-HNHBy$M2CKhSs2M=%{pK4(ybeh1|GLWIa>%R`0EMa4jiicu{p+_9(_Xi+h$ zMTHyGqGG_JVlCpSgK1H5QHzT4b5JwTqT-?!6(jY>z$icWMM{oGQ(fctQj*pfSGC3% zXpM1IYmC85ZY*-HF(!SDN#2dAI7WV5??qig_Fsp`Y#oT6qrTM3yk&OG_Djddr(h#R{HwUmn zjDvxUJKtCDH16LHQO12krNg+-t>WcD?huk+RRmPm-&BGT^Q)$GplPK1qKfy0h3`?# z=Q|9t#bJ;Q56P#hI}P%B%rxB~zksxEkPl5N@)3SMxTr-SE z!8q?7ri}CE;Wv#lHGquszlL)%&VeKNj6upcTXf@$HV68%i%_yiHVH!=7{zLRv05r~ zZBgdhqRh2LnQMzO*OmkFpCgpHzDBpdnCpJ>{!x6K!(0b+H#qEdpueVt!CwD?`(NyJ zF*gLtrqTa9gKfJ-8SMGD@Vu<92HScF;~TvAGBw;_-G^Bdyfgq4E7V}^YQwFQn&jLP;jD$5vxMG?l>AA_pTu5#u14PD`5Fk(gAL< zqE!G=*-$D8lTT0N7B*5IoXBIFe}NrJ<@ab*GHohKeuR=#(^Q?xsu0E3 z(g#rE=W~A_&E!vpal?s7m^C~81Oin;%?PZ$j3MdT*jf`ouQPEtjPR6Q^~fXVPh>-wT%4b|(z7NA~s zbQc`&&a<<-z~+Zoc1ai5dnwPZ>H;@=*YSi2KxBcs`enHR8V(j{iN^Y|ufQTcqzjH) zczjY9*!(PuAJ_%R39+DsjqpmVEcWmw1JsY5yr9g3$8 z=`cDJPaV=>bVzaQgq{7FpmS6GnW}Rb&bAQ;>W{*a{Phm$h4c>Tu->6g*x8|(Itw)_ zGr(dViEKRcig1pKj?+g)hxJjJ;nVD>qz{W;Kp&L{I$6-D+yxdZiN!?LL@cNmIu4!4 zrcu#hbRwHZMTgM|HSnFVqZ7^A2AxID7LfkP0&UBLw(S5~^=lcJen3p8v9o%=be!HV z9oGA$!+N(mVdvm{qVvpZrhdJukIqb-fpLzGj?)K6hxNhHVSR8qVdvm{-^qeFm@u(n zKr}X&ZP7U>T-Wi}3+XI$SZC1*J6W{pEK;6E2mS>%`#_s)$6cD%XA5wozb~^x~6x+PGNeO&@uWcP5(q^aW7j*EJ#OmoGwcpMn{{~ z)YTDsPdi~}Pc1r&6q*CntLH%*JrnNORHa-8@_QinI*@!0x*rUQ>)p>o-QN}bGD!T49jcYgNV+fEdF|@H%P`i;WQL56Ff^kLBd58;iS$pr9UEF<|+Lq^JxLf zFSPhM{K7y6s`xGNl+&^7{hve|A{uyBY?o-m*C5w5+VCr2mn(#HgdDIOu594l2YNvT zj47)0P_);WP6Z8p(I8O*eRIhifu!rhFr|U6D_%m{v=RP@>!W|8CY#2{vkjerh}VJg zFqGl1GZ67El6oNG0@4UXlr(Y*MBLw~0ug5$b=MGqi0fPhA_hz$*Kp6wDSRwrAMW|* z?fgSQp@?8gUjXI z;MXBZ8~oEVl@IvDEQb%+G{@-!`c{R)dvo}JzSWc_AMnH+Hq3W=e1V@ZVn-g|(fOP_ zKA*e(Z95*YK|XfZ|BLPT2X~QwC$Sy3?g?1HP2}WR?&h>7FS?sc_;+94%>xt3y$dSt zj_r7aC8*+e+)Y1Xyn_alm=Q|DpP))g8%$qI%RQX-=Z*I$cW?VW+_66os;2^Ke}3j3 zPW$tL3zfS!W1(|@9@I=F)c*X?Lg)TG=w8A(_vbq)m4 z<&b9O?7cydzx=9MIeVdt9L`?KV(!?U2fDKDsP1wGe}c_{o-D<&J->6Y^8X^1IQ_rC zCg$VZnb$0F_KHkCE1AF={<7W*j+~}UT6x0p0J5dI}-4SjKAehO#N4O*0 z=#hZqz>aXEN3zQFl2aey!O=ABJu~N{xR09le8tB|d(pJ#kA97$<~2rceZ)EKJ^P#j z%Ed4Zf7P`29P|^CJ}UmmmwI9U>6IeAR;X!Tu>zAiMV?t^aK;}of5WjG3rdlFA2d+> zar%RXXK1#Ymm3_j-CV+>K+iKs$^k3YbU(CQ1s=axZlLLY>=pxU`C1=yO!sxG_z-A$ zR+4iKG?>X!A9bT+shiBRV1|k0J4n)d&svTZP6#E`P ztlHtlsvTae+Tq2j9bT;3;l&=1zpYai;AntIc+s|=lL5FMsDg5qAOz)J*}z96J&F|| ztcZjh=rt4a2(wW-R1;(u!iv{nE7r{tRxuZo$?Hd%@{|hGT@O-Wx|L5UGw@KbGfWp& zuj+asOt&vsOmKC_)-G(ubQu{U0_D9=bALqahJ*;m1~9Cd3i})UX#*IxShc|5PaD9n zrB7m~6Ke3M4Pe;4l#^%hpCrAWQ5(RX&nTNPgl;d&_)tM1yRQiHmxhgefa?UvEA08> zvOQD;$-0gF5`uRg;i4zDf(xHjTfxEMh}6CLtcujxHaYDYqCE^A_$4z=aKueta^_7 zHRA;i?e7515E9$Yw^-noBzD0GcixZka{B<;x4BD>-(9TlV_jh1**yDcz=`0Xe*N75 z`Sx(`nqKEuKs#$(7o6x|v02NyAp9n=EF!5_@~v}_%#&`<^Q=0e_YT^63Vml!^10}K zU!teuK(8;6(_xTPE!1J1+z4k2v#9ewgCGW1V{h`TM7i;K9vDwu&7!XAdFZNYmk#S) zog%+`o|lC$1U)sHjcPPE5Qx!iRD-f#mc4*T{?~Hy3w&(hb>!u(087Y1OR3XXIVYo; zjbYAOgW-8jZ_O~Cy&Z5VGO{-#F&>HDTao*QG``6DL@WfHi29+bKBup*05-(`}5wPtl&9eh65olJOGzk`-9c0%K zw=rU7+g4$Y1D*g{{4p)-M^K5@hv03NeTiU{%ko8M^$ZauvLgtljQTDa;mcX}3}*(| zN$XbLGr2cPDP6r!EfOOLgs$GNS~L@oLyhidq*9N`d0Sz5wgas!&l7R5Jj>9yV?A}t z^Qfx$v3wH+9hS%6sc);8(zR}0PF=Gg(fd4dyILNATS#!5*f5ZESRN;iEDz;%u{_S4 zPRrwj^|8tT2laDU9$gt;WY2-N!}2(B(5?)J<#8f(_40MXx_T8mNe=iDydIHnzl;OO z$_xQ)qJ}@rq97E98FJ!4++l{CaHkn^!aD77PTCGLgiJLTUS>*be|Ey8wR+m2wK2*v zIkR=O)r;t&xKlo|jh7YO2Nr6y$EnfYOdv*koEkKG)R#Q%w)qsEAq`|BQfA;W&IFbD z12PAYFdva2ukh*!oK|wGMygVcNWf&j($s_)C?9^sX>T^6Wy;?4W}ozO+M8+=R`#YI ziQaf-|8MpNn`4K)c@iY0xs* z-SN&r({cKs>99U%I;;=c!%mXQ-mC>dHE3n*OAvI}8y!h)*3&oJtYh>x>#*MBXXV9L zdB33DV3S8pkHSTAHYqv(<}C+q=UF)%;erxi&yY3B1yD+h$4I?7KdZH)0eH1`+>J!< zamai_Zrje&>Jb>97`_CF4828d>UoTb~#O1DVefxG(nB->&lWvpp>#?I$pPADuXN;Wi(R_ z-IP%d{VH3@a84!GJFt7I!<}uImjt0qr^ZgDXmmQtmQZu2l8ZHzAgI2o^DZG~;`!Vi z$_|gLnu(`#D*Zijl&M<=VgpWqcJoJQNIW3N!kELV`D|oeKo;c`{UryAJm9i3r`C~U zoU6^zqNo}op}oD(BdYcnVw%St7zEW{aIRbJlQ6rK| zBl0J8i#nN0W0D8iQzvt&&Rzhjll{ANQlUQVRVAB8kOM9H3tGms z>Siix5rUiqM=^^krj2}ua!g!|ybHS$af69!PpDS-GA0uBvH+-|T6H#Z{O(|)7&)WJ z6CZ^HAsquqkm|CBW^Sf3BbQT!TF|_T1P|hZOt<0>K+znz$s6wO4Df#wgW@}ei|Sbz zNW(=Y$R!&Qiirh)cGKGE0#KnV{OaiUAWgc$uZ?~W7`no*-!cw2y0rVEU^fif7PQeB zE4Up23wmH|7RbggHdsFL83H%6<<8H#9z$|GG46T{$??RvOPt`SyU}qB$??Sa<}oD4 z6Jz}tQly8`5f^YgB38$c9FK^FmwfDB|HC8VfBx&gJR(+MfdAKc;g%TgJC*`^k1F{XaASS!E_wS@g!ItJFS9%&IiE}Upk@!1K;BH*!m`a%~e!j z|63|5z`k)r1%@3^r+S__;5^miH|!U8`Swd9K%P9HPWAkLKo1CncLoIJAH>c#K^{EF z1G+iR++<_;^hdmF4&8jhi@mUV!aL)T+W)V8S0Izxg;=Kfn`;7Irbx-;$05v#4=W~oGPFE2rQTWJIgb~GX5q@f{7*F|H_guU0D*W zvs^3te+-sbJ`_t27Q+ygkPANMw|kujG8^q^*^5pl%F7?~M@J6EfTfWEeh0zUoQcj( zd;p64(+(KA zg3&IWafo7xJ)_9$Mf_4a>Y?Tg6M{RuwUrxLj0%NPT;RHQ;T7VJ54g3Qha`Tj}1IVu&-w?X@u7EZ_U zr~!CDPph3BO{8Cjc+eHF(CCSorcR#*ER4jeL@QzI6+@Vu^}XZt z>3iR+$6an`RrveTS?9_Z{0SqbwDP@u&EO~d{=k#4{5AaW-sxhk>4Vt@%kk@A~j3?uc%OG+%})`y13k7venLq!zl6 zrE@U7oeN!v^N4EXBst)Mif)g(prYFg>Gq<0{(@T1x?NP!?aYg6J)3#av7T9kkz(4f z{;Xo!AN;HyZ_W9|8O{!FVly#U>3GwgUsO1IPtvdaLxy8!ZNKq7>`l47g+J1~AG0;N z9y9(YHURSc8ej_T75N1fTIc|rdJil&zsNjbJK6BGd~9WY4{~g#@jg^NGSln3;8=H_ zzP<~La{%eDbb)aWApH#;hJ_-do^b>SU+g5*FD*wNYvq1Z#{n4~>3dAU_ARz zf36FRNB@edULMPpBHB|Ynu)_+rg{XI&Y;0r6h1X%;eb@8mKlzW208S1h;e|N@;kSt zu7OEP+JeQ2?`C!IhWdes64GuZq+0;?uA69UZ4jM~8Lk=&&xGPS`1&Q+hujocv387(l{#$2knlDI6Wvg`>l|a5`b9aDLH= zW^M!}5>6F*4&jJdZ#I*3aku$3o&dxe==$u*R8$o#3y9mhUP9#e6$8OcKiN(Y6 z*Gt^mGa64*l9cW|?$8|wv=4a#naJon0R^F4nxD+M%tOojAv5zf;E1dn3eXVE#$S+~ zs`Z;gWRas~k3(uLQjUDoe-SPjQS_(t#U7eVw0!0=4{E-ZxT`UorN;0UFwo*3$9Ui= zYUC}&dQG?>kL&M!1n8v>-5TVk?6n4Q8|!A zX}rXSS}Sw{*~GbCCjN=mS>TR2TJNP=w*^&Glw7@)T;Bt%Ml}@$(}tmC^rJ`{_hXYR zQ2z(J;NWg4W1yFTyQQYB4(qnyb5NyUT1JYqHiedW3|nl$bVO2nAKli{%DT|zJ=wPw z@SC=#jR!U_K#sByD5jbNhxV_moRi>JCo9LvaGC^HK}D&T8qIV^2I+$rx~MYzwQM3w z`T$tWhAuc1k%XWWG00VOA<^YOjw!+~WkR6oD8x4OlsnpZN^|chO)Dg6Wg|yP%T7ly zm9TV_E-W3^g{8x~usD>Oe(5BQ37}^Jz&T5w)&+*AKTyxhTR`zBB^@25OGk%w`x)S* z?d%^lTlLSRxzK6Q{H@fzufGgHv=&U+1{W*#YHB`xP3uJhu0iiZrsq*&3#sF`%TO&N z`~+~LkZB`i-WfocPVQ*?ame%o*fFx*Z<;s}9O|HmB z6v%{YtnAR^pqnLszruZ+mGRL^T#(JTe1v=zOWtt0lk*nhd;r-FZZ8qHZ*Wz7ioye^ ze}lVGKNiz|iCLrJb2p;Fi%Zd`%J*T2`Qls@8d5uBvJ*R0HG2sWs%j>?nSn|~!=Y*f zsi81vE<~=nh{!LXK4*5eZx=F3iO&M!(+*Olv|Cv~T}^}(OCcszWiWsuwOhHH_6pMg z_U{Wa7ab}tV{Y&OSHv5KfswRaeZc`I>DknpZ#qfOA<`Ob zW&a@{-6kKrfd>&zqQ^)CO(dLgovpt|XVF9~B2m%N#3rIsNp$K^R$xb=n=rD06ct4) z<4GL16TzlVf?wzaZzqCHpitV3Ezs?I(X3}W$=^=o4-xq}sOjB>JS=22$XA2>lSKYD zB7Z9i(Q?l=gvL5WavPEVmMBd7FAd~w9U$-xb+|UB85HJqQkbGss3i*CFx;hRUoEw7 z0D%5W{!4=#CX8$l!9?j)zGL|8y=4C<*Nj%psf1U8muQ9Oi^fvr@U zokf~GOijIPYLPa4ID9R(M4ZLM#wG#+-G#!*^)nGOUm{{))$%|%smtDSDquC852N6S z7StnijJ3=;M+oh|pc%s%sJRfak*OFq)+ofU0D39Pjf!#=O|W(#seogG5u_%VpXNfv zM^advAuQet#-Ytb+bT-`X~s+QHUDAPiUt$nuhaU3{nXIwxNG77?>eI zJz{~JZ$V<iW|70dPHm%VNWDz?Px^;8sF% z#m|6?ZD=5FxvClzA=<>6%v5SDC%dd!y%>|CG zpvipfTe#EZSH;GzhNjWwm&L|@fjeEzeuZq@&CvT;U+|&J?K3v^6Wr8QbqTTN*>y(UjN6@{cRG%(6jS+;KLq*jt9Q&A-2-- z!0p2gaqCADt0= zxQC#}10VMg&R29h&j`xF0V2ooithj7MBsBc3W#V3oe2EvX+ZhEI|%qLOcfmj+yuM! z9|r*k1q*s#_kTJFi1GYp^U-#zeKe-`9INsO2dDIU!BJBRpF@uT>y%6;e zd*ExNHKYGP`DF+q`%~qAJ^Z&fRM7jn_E4eT*QFzWD%>CH$|k~Um{;OYs5#V=kwX$> zl{f`RFN9qS7minTaRBgb%uPA~m>VI~tGc@)#M9REd73GKybYH46jnK-I75iPA<2>) zh_iC0Mc}LlY#D_K*lS`c=KFkrDYUGNMIv>3Dwfg+r{DONm~FxC<#-pI=+4vJ(r%XV zdx)ilbb)=B^0er#a2-!i1N;$)t6%Em7eKB?XR%-Wi&*@<3r<*gnuaQR8NX*)nr|1_ zcZGw6o{w`5ip94&iww%yAQwi8EdK$hNE@6?gb7l$jOEBFlkZ20amjxGtHjWx#4sWX z(ULoA=V|OtLH@)Rz)CDG@J&-E%Bm>g*E}7~?6WD{v32P?50F!2hk;YB_T8cnDk_ob zI9+5qtcy&Cb&++#PLY|dL>|9XlGvx1n|2KxQr>`{x3xhPytX7>UxG&3C1RXUX+=Ae`kU>_aXIZ2yIiYTf2*k7DNNrxDnxK1%T z;Z89+;Z8B?uv3iBLR#vlX6Xdvs*UUur9|=*eS<1I$4k^ z#G?1A6E?AdSdewrae60oSnmYjW>rb=g(3I``dnXIhg>0~JL8sURLAwjp3mvC- zLWlKE=&;_2PT1KAk8e6zY?sf*!I)CRi=3U&8?M88!*y71cPH#@_obUeL2aBansMTA zoKrM9PUoP*ep8$)myXa`biz&+q_gUm@dhlxE~TEw)BtH>fX{j*D! zT5u5b!h-WuFVR0@Ljr;;*ih(IRX&L+80*cdq+wDGb1VVGsD=dmqh&z|pv0)FY^1jC}7#iUItp{IdywJ9}Ro3og66wkeTz zUhG|V22XVy?ALa(e^;@800fjY-&O3l5UAL{r~K>><5C>#-&5=_5c}!G{(bg7)}UnQ zk77^#F6LnWwoFSB;mzN4vRS9tj6%WQP?Yub623N1ul5^?m3)oHeT-H+4xOR}dr=D8M@aDABwd1Y6>U;t)rGmL3r7H2lh%_*I*%3Nc2?&`jm&r&bUp{S zF|svD_ytjN1_-K^8xxJ?X~l1#$agX<8U1)FS?5)(c$uNor0^xGAFAuGph)W5PPKNS z7FIAil9<-k1&33*%7I0;iofHOu5w^?ShtWi(5GMOQ>rq|xiZ4_ED;p*Dd$&`RO*{u zXtT-eVdD2?7aY#;_My_$p1waJL;1Ek24{Hx%H3%_$2z$?=F!zO1S`lo%tk#mkEp9^ zY;ZP`B$F6NW0S&$Ltp?gHv6G24((1+@|sRIfKH>JR1(JG5vTl8Z_4juR8jI94Jt~0 znXCdhl3%5!BXt4lur5Fy)&=;gEVw12!rw@?j%^qbszS z5BmytxF&=p$3hv~sJ&(GMfG!&#ObPyjl z1qJCU4lUxt7z)!BTFAAP9yH_WBU#P>Sq1iw6d+SG8Mo)5C-^K<=Nd6yJbr3CiLHPZtv#25L#$`JImq(3s8AurcHQ;^|d zK-d#+OjF503#g>?jo6Jy<3;#eGF8Y+W{Nt5ysl>IAuqh*x`!jsk|Kv^sgT!$Sz>wk zhiI6O2b$y-<-Qkf@-4w1_lg6Q%<|lmmMwPD*X+LUE$EzUX^!ZV_%BT3&pVzS&$p{e;FP(aounbWKb8_ z69+*?b%kg1uv-BSm*4dhBYhe`*U`Et#qSAOnkz#6x6pc+3|W!IP@O!KBk62Tv2h`fBy9crNCEYzkRvo`9^8NuhpgLQ= zFuI0Id!3&XT=<)$cQ{_s9>HL6X`v754Z*;pQl4iTmz^ga9-BRx(_(Ou395_&P zPoj@|xhK3t82Y%Ed$P(Tm32>1^+;tsGDAoaAC`*;DwTb5py-!OACdIva~Co^3}*aQ zr?))@twhoY_uHwrE=zYK4ZY=gN^kS>1RddiI#1VIms0k=LvQVQN^g_$yXviHl>0kq zoYLEF71TJ=+mrd?5{KS?SfuneWsryu+6eiH{4})OVCoT#^dL%`@TrLzgTz>$G%UGc zO4pVOBbro+?~4ig^y0NaVu;@&MF=u`DVXSG?X+Sh=?gMtul zKw-37V{^nLjC@2qaPC;vG|P8bUfw`1Y%yFh5pfN07;++hLt=pZ(I!&-ZU-Dig=nx9 zzlAccSoH2q@5RO`Rj(0)Fd+W`-0L#hvl@jzKxuZH$aVuUPw;Cas*D)RHN~R8PZ$;x zM;{ARV+Y8y#UhtYl#wN3FqcL6f41DStpf5 zMdfwC>H~w%qagXknkTMgns_OK#{W#JJX<0vd@glX?5-+C$ox`a@hQj36sxMy&Oz&W zpPW%DqJ1U+?da)sPCb22zE~=Tvz_ufa{19T8C53M@f&IKK$)1sd}UU-NFEalgC3Vc zVtAAHMWtfEX+tpDY_EcQJx^;semkhlTYO?S%z2y_>csir)X3y6Fb+aQ%mUmb_m_*g z>^_-Q0hQV!*H?&mmwiONxBN$iDCA$IOY>k+?fyG(N(e4;K!u2sD+VKuZmuR6=2H}DOA z!MYxoM`Pv4IfCN7M-e8dY|ROtJ>o-fFORl-`l0tM92jzeyz?ADU(?qPH^yi<0B>nb~fb=hr`FI9=b z{OwFRWS9t)=4y=oM11g0L|2{!gE;j9S)tkz{YkL;G)57l{zhj(_nNSOD`F=>aS(xY zi~(>sX4eeBO3?-}QnbhAgVkbC=JUYf*J~%{6aD5w!lw3PPL>7Dldi`laY@udqy`56s2G#?pm56qmYN(ZO zs|H$7KsB(O64bz{^4bUyTt4tVQiah(gpnD^Bbo}#?-ffq^g)MwCBM;1T?+1mMu?Y~ zut4t%XWfbStzKeout$ZmW~AuhUPP{CD)R1>i$;ndYe52)zl(`+zztgG0BH89f>VJ^ zko!<@s;z-cs9A|e6bGW9?@XF-qJW%KA9$`b(>iM@&$Wa+S06lHE?JDqF3)jc+l&6V ztl{sVtS~Ts*Z>dz`$*s>aO$KW%T_4!M~Q&uf&eNzk_)n~h3GiaR7Uj*Y3h|$dXWlc zItcbw1<_|9D2;{aAygEmEz^m8!U1LA|o$^b#62F<{-ZS+^^!un~qYR2v=jpl)!v7M1b#kW*Tm278J%Tdyi z*2+jN?C=`Mma+|=!E)qi>~J22LTKgxf`sUDIfn1U<4%{$306*zN9b}n$;#ivoi3N- ztejr@pv&bHE7zT9m(N&*+taSorcbNAqh8a#$C_c#tZ1Io-MEPEsI&7}B z|MZowjTTAG^!aM%mqurzY*$~|_;0>4`rjz2j0s*gYHh=!;SyK^j8Qqom zdvrFE^wFtbZ*ltCrasew@-UDm;QTV_O`pYW>GM=IMOKedKFi86%4hj?jPA4GwKJ!$ zT{2erEccA<>a)0a@wGiVeeIZW4xc4xqVidqCt|^PS#F&uqSz1e(g#t_D6$tD zkB(U*F=jf>JTJPw3n*^KDs(3hAE6FM=a?5;ggP-RfQwy%KYlsD_Dn+RYZURKB0X7* z98n{RCdVQ#?o|s=6Um)kLSRJV;$le+)pyn!AQYM; zfuK)6bAkM%PQ>JNe$Jf_9tE`X%e(4x?!2;5VU#z{vD<{cW|vS5-p zftM5mZWW_L9n+zLXdeM1<)*u&P5>;}o`-G~YX!d16x|^FT?Ww<@Je`%O3@VXN0qjwBEOxcra;7Wb;4r7bbSh#OWAnP4Nj3Kr>iO8-X!P)OnY8#a%?Hb z&rs(iw#^U&*$eXL8RBmCzHFR{XZh#lhM9Qi?@iDB!`ge_ESyN0Dm!Kg zOIS->=MWs}=@^10=MX$(lRk$LYF8iD?;(%A*7fsOhX45dm7#JY`rYNV*09$Njt?Ol z9cNrVCsCI|v_{7nm!AlB?B`#kq+>t7my$F9E(t101K^@Qgp9Xb^X3T0$M#+I4yQ$_FFMlT|Tz&I_NDR99w&n{vqVt-RfiembuE@ES#&$+SK{^<5P2$th>$o zH*<3q%~M+>j|yr(wn)-@4^Fy#HP3m{#q;K8ke}IOh?KeW)k&9$?+N+>-lF;Hq{~0w zG|(rpKDo^F^KpS(?q7~gq>PsZeC8yxs1 z`4sT%lsqEgp#CfetQFQU`Y!^LFGix&SY{OT-wG%HKkU5+lvKs`K6*}{Fby-nzzj@a zLiYq1()1+qByt*H0vQBEL_|acL`9fJFh&t-_kDFvb@!mZ>;L}WdT+h=*6X#Zt7`9ExoX$0I#s*Aqwj3^N<{ry1h_$LT5C*! zxvp%O2xuOnBShh6@7Uq zy->38G!K$461&!6WIQZBUuQhq=_R0wgP85wK{y)tK(=#|U?DOsq2~fxyb$PR;?+B_ zu)9NaZNQ4*gs5pS{Cd1t*kH`iw~9jzMm3%~>3Aosx5XuQ8rP&h-!;tN{GA;BcF^T- z`6K_gReAnj`f$k9MwgfUw-1LTh==A{)aO2RgJNhgVTM+7zU96ik|AR6GN{kJ^*pOR zkLvY10S5NhyIcm=^c@kuNZTkGnERN>^o^2%xo>oAx!Yl2UtMU0-{=T4uvTFPHgADN z2DbWM=e*u|n+;xYY<|BXaO#Yg`k^TM>HD#|KVSU&esxMOa*==O1MVrkc2V~k+eO`H zY!|-IC|}bs9yG$r+v8g}SNkt|5Zy8;aJ8Su_O5uyJ+_CJHDqVR-Nq*$lE?PGf5>o^ zx1V;aKXR=R%G>{!t~G9XmDi84SCVvzC?SFKWe=$~&zq`pVUVaph>{N(P9+fBf{-+E3UBt<4MgorU zc^-3)@$uOW+;S{?+@KP7`NjsW=<|&Y>j@)#JKw$P2u^_8`Ija+xASK`Veoc-XvY)A zMY#7EDhfF~&Hs$?PZK<<^)4gv+>;pp-IkJt^_riGWp+8_QVqjd??b*~8%M#e8uQN} zq^|=RPe|YtxnU{gh~)@U0NHv7!|#Tta0A%DPgr^uou%o+C{XL;3b%_JccJ8+#1p%~ zUVaouc0pJ@D*U^#e>q;1?>72nj;KIZzGl3gn9}X=23j#;DXxUX`rXF3w7u9abOqb* zJ3CxwXfxyjza=7m590nmBUIHo-$zy;wur8fD51*!9GL%JvT7>=dksszWfW6VO`&O} zsN5^Jp(pGOi&u{T5o->@zZ7L-2JIrH6lJ|DK872sxgC3@DEs4HDPB$3r??TstM9Q! zfUvu5pA@e?-DgmV$b#n#`Ib@RbH;3WT=;Y$s>kzDLR4tU^G1<@3&O4xRj}V-LT|q) zmwOd28B&GF_?M*A)aGS}>3n&>JtUk^k?d#XD~kR2d9+$S=96$R z%zhdmh^x0F?t|O8PTj74Z!3J0a~|`NhlEcYl!t@^uS#x{@>+!3Fg@O+9{HN&HaEVe z4hj2}4iVAvb;Etf$NwIBSTn!W7~+>2L;S_aRib~V81%Y4Bzz&QCTxW|gQK4CNx{}4 zpYZt(_V4tBeDda>ag-g0BuDw@A@@kIdcr4XmneJ7Jrb;*@X2u$fpo)m%Rn<%Dgr5j zTeEU1#Im;}L)k>@KJnsPQXgpXVfYfoq{H$^@a=~qyhLdLc?{w0kMJiofD~g3%h3SB zBf$+v+#|twy{ByoY6X|5-#H?W1c&PWVZ2JgDEB>Mry0EACsev+;8V6QpEm^c5)Vg+ zg_Q;P$a92rZvw%P)$s&VgocVI^`0I!o)ao?WfwrM^sMfvdBF=HS_Q#M3KpJ?S8T5I zFg?Axa6OQ?Z4}gsw!)Q&#jaL-2jjk2Qtayhk*0Thz~2SD zPX{<~0?_MY$i4bqAnQ2*u$X>u^n@c7j$Xv}9t~eN_bB-<1#oN zf}?K@N?3`Kni}HWqAx?drL$T7o@W5F3nW_E9dHd+G~4vTWVpKmR)||I(gEi&+P_(A2=Y&U8lf7ZQx=}e?UgUGdd6IoRE;wAMjs1tSjQLmC2N#xT^uv8x~?Wq-2tV z`5chfQFnvJuv*~ZrqJMp^N`iqGBdsVqpBtW$$HcVt)>eO6LCngpuR}b%^}@dMK>e| z)KGfw{S5OUzS$O5x|l)&W%Vy|A>~Wp_#Dvsvg;xW} zb{NV`un?d&#FS5s*kE6$CZ7PXzbsi_nW^EjRmvQ9H|9>F>rES)$g@~|9{(iexA zWd~~*_94e$CkfS=JttlVfP0t>(@J8$&BXywxiQzk+&MMtpzc7WXd~OOs!!^p&SRJZ z`l$Vkd7nOdW+&KB49s;ZUT)m%p6tp;jKt6hBNT)5d}b+TYvv97^q z?Pi^WpxI2g!Qc*ZGm&F|V(J|A}Yc}9oZ836OcWR0ufpu^du8uLS5FASbMbV?qP|Cbk0w zc&%1ST-et;3FNH4e5i6|rHK%mxC!`GGf4qGue(3T{3ajaYA1~2Mpklof7~2-D~Q4`af!0y zMw$mo*C!u0@>@Fs(sdxPSh40XvFC zc3^1t*T!8j5QonC!QiISCqEdw_{ILdpWRI*Jgs#mW`Fs#R_h(qIK@q+++U=4bnF*L zJbLCgS3F9rDZ|P@X`7)N;?b>{CKhM6PBQUy;;m1cd^s^eH~Z>_7_FPh`gdZsZu+pZ z_!r$Qcb?vI#V7N6@uqG%cdU}@pTZR8h)>D&``~uOr{wxKFnv>es_>XneA?nMdB^H& zkIBW_KMd2kW7YnE&iqh(YGvX%&09saX}Wi;T=A)GgE(lKe=a`7SSFWd5TCL`<1ACY zyD-g`YG+p1rWmv;2CJiitnXwmHLj=O@iP2t@}aG?A)V8)8}Cc2ipiixBb*3>xDxp~!ozTN@TCB>}9 zIFmQ8LTy`^mzxl?L~C=Q)p|IFd5Qc2eV$&744o(1CzHv-MufaSUK~l>aaA<0Ed8nIC@uL5k-i#xwM8 zNaCNOce0t@HGUvc>w7nNi9Srn#eVr)B6E-cUqx zMHkSv^irgW=0(1#WU?63k)?l=jVtINE*mP2CF6|)JV*em?Ld%{Nb8ruRDU5^p6Hxn zrrIUUdBJTdW}=vyV#WlILQ<)cvHl9uf#=S|m8*~T0q|Eu%Q^2O!at!0hpQ!~^&p^Q z&6YYQ;J=^>^|!Vok{lVy02~ByB6*9E6oHhHyhZqAdJu`k-0DOkK1wkYaw`#)-jI!B zA%p+U2=`7FUp$#= zKIhSfh-K};b@Ifa_U1tS7STSPcXCef_8J0=I459eHve>2Vj->(k};iYL=e^*Hcp3u-%RK^>zO)TtTr zd&PtdlSjIq%utVWV0+J9P{(J=$2kUNnp{w;oxLwJ-8VW;-_%>=GkO2k-PGIeGkO2k z-PE(QOnLwIk!&-(ska0C(0!NZT{t;`bjvZhsrOlqDKFvf?O^iZ-Buk@zHy>sM@|@G zMn}`Va~s*s`@AE#VHXj|Gaa>@ZR`8CaM=Hn&an0;;P!)?nadme-X%W*u};}ahhn%wPMP-GUjr7ljq z+j9dad#Q^vd9i-8_-Q%bk$%0%l$(8>ip^L(UK@&U#4m$W=@);F{B;!rOUxnhBg4=O z2)$I?QG)7ND-M*Hekhats>B>x*w8mT^uKn8{$_XR`({h2@brVo=XN)v4k8=BJBVzY zcDO?9?vBZoa-=DbP*{&4FY+L=DUVQCd*Qba5XeuMX5>h+A=zKtB zflCnH$>(-pNvqe&d@8TXX4vm$bF8?vpZQSwkJu=8=R^xK80W;p?!ah!o|xL-%M1^_!i3;&Ze^afds*oA$F8mq8#L50Ia+qgPT#aCCqWdK=i1# z3(kaK_BT4)?LrpX@_^m`P3R{{aJ)#zxh$;K#(V=~B+e$_FFpXS zl#xzCqo?q+MHWDL1g-oCk*D73g5>pZW4kwXJpdg*gIG1=DX%0bQvPQgd=KT{;o$o# z|4s)#SoxpzYVDcwZ~!JT(Hqi~GyNREm!b^m3*lJRpROQW55OT49i<}q+DYVE<=2}@ z{4L6FHItcME3O@CPR?EkQOeY|Vb9NP$*8U{#Jsf;9M zxGA3`gEA8LNis(diN#HC$>kh9B$iYvqKmj%(>IpO=H~KAGP!JSE}tZm9L>=~Vpd~- zIC@B|a~TggTx`jea5~SF#ob8ZPCio>x9W2^`Apg6wJytx?ah;Ows|T3CCiH)^evpu zGi7lr_|6iZDf_rqvb^j%lX^&kb&BOd4@oDCKRi?RcAaE-Eyp;|ltB-P^G)G&6(obl zN)gCWK@z%dtSR58b{{JnGs%&Gewl2JN+E+xNYbYyAY+>iOfNg?;cN{VXyz0t17)7! z$Ur|%HI*U~JgXB{L_#+ekxZQ?g`(T1DWRw%tJ|Ytk?fo9E|OE~ALqR3K3?`L7s>A9 zW&gmAO!)D#`=&cm(ht+6lvH}Al#)8kaHS+@BVnS{MlxxJl#=e4p;pQroevGr6wv-G zbD*P*q@(=M&{2M9=qNulbd(<&I_?zpXHgsqJwOW|8X|9#^%dREHmCfLDoNx@Ieo|( z*s-Kal0H~5H&ICts`Wl#5P(o$StY z%w%r`x@G#cxA{bVqlaqA|4>iK&9lvNuk%P5D1S@CY3r|Nn^CWnwU}e_TW7~Pa+Un% z9Mk#C3H>A!v3`br63p~zi}h()V%0_{A@6aXlzha>^UMzexX0+t-+@uBFD&tcs~R~3 z946p02T%Y&fY-wG56xa;{am!`Ux#791nN;P{gCMsuMzgHgz@T`{&&+W?DGNpO~M{0 z-463B(T6bKaE9eoG5scUmza0HnG);=SRoam++?1@{>x?X7RwvFYfP5lKKM&6!I0|y zIheZMXp$AY!+5j+@0sbd%!l$d?^5{n2C8K!l9vK!nL}|&EN_Gx_beIrFnD{&XwH$* z=wrI~%mbU(9q$~Vi{{Gy`I#+<$wV{Hl7q8Rl z<>m~0(OrtHpr;`#FNL#GF0;bbwk&43%t|M5=R7k*pDuRHGgG<@SIAt6JP+R9XDz}O zZU-lyby|S;==6BA`nC(ql)RN7=yN&RsT%1uXLIcKx(B^fjKVvU0@~# zeckZd2WDWsVPr>DKL-ug&n}hjL4$SwBfP~j-B%4(bNi8~_VZXu$3Kz&nC|euX6V>k zm0z%$<)uek){;{#@!wKoPxtzIc6rjqSN=hiSXY6#DIqYOh$zv_j-RIo$C4w&;nLh$XLvnSzV8STvpdX zI7*0>we=BvZfy;if?!RmLNDllkGSAMv-3D}v?}7+vWQvm_hWj;5%s%B!>K+8#w!>Q zawW`rwl;utgptOJ)(PxZn4%)z5>!PbZXceiwHGzuef_3AyhM z*nL0_REUa7K%N6+Fe~U1kSDX$s~~V_eOX6`fg7-#aJP<1-O9WgFj<*5_YIQp6bV;G z5z5LOQVU1`K?gvqgO^2R5iUY;0=f?gJ?GipS$(@m=!_cK18*PDd*E?vWWXU8=K8h3 z^+-?O<~dr7Z%ByBt2Yd1*pEcZg=V|p34jM93N7#+={9;^aOw1h%Sm<+UOFyzlCX?K zeD2kTf~h*ehW(Af;yuR-uwzT!({O#h8kF%K4$9J3L0xLGbmjPb|-yfU~$M6Zrlv8XD zyNf}rm5+hAdnMx8#dyYger7yp0#?s>cEtt}{(N{F7}2G0JVM7+a2$rC{3bXyBlKa0 z&eb1g=$(Ll2V~#J;b>P2$7VQ6=(rP(IdGJazG6Ro*TPrv1{~Yqzy=*7yad@i#R$9T zeS?hcTi|4DZR*_E3g}>Lv*0Kpv5f6X_+)Hb;NY(hUmm)*Nb_C+k3QT}-xcAw_xKeE z1}a3wn}8T&5cU`xrEv875n(v?g4GD&)RtsY{03Ro4jG&!;ru4)*5!Z6#+H}uxBE$svs`Wd0&hG`W=A(OXTvSFbpZ_ z1zNu&F5;Iah(fL3CoZC0x2U}7MOwdaTtuJ=qFC$qtBV-g4XfmEhk-iue$7!WO#RFz zLAq=G+PR1&O%Oe_epxQ!<|c@qTEBc3@lX>)FRfoC5R(ePNQelkS%O8Zaxw2V34$U{ za1q}(L7<2;T|_+c94QEjINwEdYJxxsm%51l4q}Saz&eU}t&5r5BnXOli;Gy)1kqC~ zW&dJHkTP4H4TXysql(b4^zU?ihdBRYvq1k+tiRX{1ff~PdmDRc1A{nH&7C?K#AtL# zDN5X_bJo5IUT1n+uaiG-qkm2@LN-dh0MEf+I~_xUDia*}=0V7VxFG~Yp9@Mb=#Z4; zwtIEzX{fs#u%H5Z+Is44jv|6mpt^ga{Lt7_w*UfWxoPEck9i5?*+q zY$X%fsJkQz=J9#zu8ZuLKvlQOuj*F$Ro#aDZrz@P*yT^w z?M5WQO$PlMeI=7%-71)>TjiH^8;l}Qb*l(e-7Zy0^dsg9)a|{9J3MAM%ML#ROcRJ! zx(6Va={X99#?C=vxZIi04(kw1wbvq}LA`;~j8pFeWxcOPa!<28=P z@$ysSYYaL?-cx>^RFil|YAJvW=)_5%jI)In&p5`VcSmf`>9@l@K2b*a93#}m-O9us z$L*OVOU-Wjaj|)+>F;+GyEK)+>J5~=rb_yCq~D6t=1Zyk4i0~P%rr>8JU^km3XC>x z6l1$uuM*9d;luJQk-yA5a~$Wg(Y*c$4ZqBk$n%{|Z_n3H+`U7uKr}V*me3 z_W!rMWdF))lc(J0-DEn?_#{O=XrB~*&^}|0+!LC(M(qhjl+zwtaB7+X!5P5d&)hm zoECIxiTZ>j^?-d^mVN-9KYhTy&292~8PwJ0g=XF6d@q|L70Sjh^xzgvEoW>O1Yav8IdRK3)kUDONAJ|PM)Q> zkk)--?K*xWyX_8nl%nGu@*CN#JDhK1mo}I@{eD-2+!1=FLGB2hd#8JDB7MGoIo5U5 zSo^@8^4x^*tw-0$5znqS)1boO=z3&)w&>evPAXl7aqj$V^Q;8ynowo7-riW+2J(GR z#fa|k<7?UFGB~2C)}$ZhD(^p zO%-eby(-^XFQgZI|1}wGHGGaLnAfBtrY-RI!j03{CH5uwq*C|eh_jCdHnS3rzCZFF ztA0e1=;OPUhzmEENwdBHabW`3SUIvHXUva1cR~;W9`Cr(CR#^@CW(U&oL2xQi}`fzKQw{K9CvV|thgGn@qpb$ zh^jz}*IJ+fuphwJ3*>f80gks`jKqtWcn(lfl6%V|6IOmVVHb~iNhPcZRKk6Qf1}w6 zS1Lwqq$q}L^u!s`M)}_TJouc(-XI%$75u%V4wt(;br>>R;V)$_j`YBZQB1M=-JZ3O zP0CmW3Wl7Np$fu&WJFe~!mEtzMPyjdx_#m+#3=j3{hm{ZQT7Q1W1mp&NS{y;)hCo+ zHQHgsFMqPn#j8f!?%`Qg8Gn3FeDz~XG66*pNkBnV0?MxvIH3}#IEl=E(g6xA5wp{V zXgLUAwOW9I*t~AjYF+AjpxPFAwjxLeO}u}%nV6|fMzu>hW`P_sUE!Cb>U{*Pd_yE| zG6%Gt5GI--i7pkhHPWXWdyNIZX!Imu&9 z5n1<|XLwSlh|BLa^M+1A7M!C^_>Aasgr9YCg#0OP23`Q7?0(2}Q$f3(4c^Q%WDopW z@ss!;4Z5LA#Mk$lJ%g2?NCg7#%5+k(eIjF<52|7BkWYQ86Ne{1Y!l03tqV2&>#yi} z2%0Q|&It#7MFxEULCcmQrOqJP!1NF6!*7GXzW6%)zsU5NaEtDU2~|v?mxHF+uZ*4# z1n67wxnj?KV9h7Q@%zj)PwW}OyV>k9wCo2&;6>PL8SN8#v5h|4_Y9<$3x`7B?d;+r zg}_co7?F9MUVIf1;_A)#f;3$`vKhl^6v9hZI!itbKbKyx(sOhc_d58TW;sW`^}ZSY zUbq!GTVkJwPd54kpzSjOnHmg7zU&qkNQ#d^(QSEmN4dbfE^25l)HyVbsTfE>a@XrX zAxF{@eLRR{PggK@bmfk8bOlizUHMf1)`M6E&?hzpLKbM z&V$pENs04aC+XAA5+1${m-1<6`*(W@^8=DxtYJ0f!lCxhPq?Y3a0p}@+*F-{3_{#Zt*0$ z!#1neBzM)z^#>56>;)1C7<++oM|y#Rs9vD_szp9_<9FupajK$5>djG=GJXYP{B-wb zlSL9xXqABSs|0>f2~_kDlOHluQ%S&f3iHmN$wXS{c<5=>LuPWT7Sp2GRAm7 z-r~cD%ql1YD0mnG)dgbJ!{#mVD?m9?a>Qq;O>&bc-hzXK&xw^=aAxL+IKIWq8~ad+ zI?a)frS{0Hnbs}0po^SjU^x!y(^^fB;?85p9JeB5JX`PHDBf5KvY{`Da~?7M9oB*X z@;Z3q_;A#hGqN*4q*d_|6#cyAV#_0Da*hCK3|SubWW1;1fLRp9@wNjy^fqz)5q!O> z7R|PrxwzsS*os4_r^N8BW?A_$hNzLuEbmO0naw~{2joCwG*QioXYF zFM}KSi1a=j-CM!Y?P^dlcaM{XsNYCK;x;poJB9AP9C+mJAaj=vvZ7at{P_BW&@y|& zJu-i}2qW{?3y#1>QTUjdH0lfG()=?BqWt}^{Qo^_HV!}T9@dEI{a>irSn`BCpLX~Obyy>!W~1myc~}E#HZsIj zPnvThYBZtR=Ofh4?{#flp>9Zg3p8&?K+OhU+;uf}JAJE3~Kx^wA?JdZeM=jx_kG$gj-Md<;Bd>UWHwh!*PmjC?_sTOK57GiV zao^wlX`jifqIeq!*nf`VB9l8^wtUFPVA$<9fMA@y_qe7hXqz5nz*~7$Ukp8Fwq4V|ookfa>rO z{=%R$w2l=d8hJwOK|Jv%up&qVUa#rQ?*~)Gk1v`2_|E{9Qd`3=0K1$JU0yb)rirRB z!}zd|!!Y8>)bKkX?s?gyy3*%fcF(j*b*0UJr>?a5>FP?;516^~aC@v&S8DA zY{6A*u-8CNWwLs5tpC4<4)9JOFA zZ(Ikrl-*mddJs+skmADwE(2-N`yPN|u^o&ES^gG-o`lmm;M#J>wFPXu(1AV-pA4CcJ5`vUtMv^CPCzTl&sBxU6+b40zY< ztZxwW-sLgd(ADp9n`)1^?mf(+7mBU#nV0KpMA0#G6ci|3e$4zd__SIljd)K-hFJ^P-$7M`_oTIV;LtjeY!1jU{xqYFN0NM_NbIu# z)kbVU70m~YlveIpkC-}r9|cO7s0Y||B$3ffdDOF#$+7*~Gm5-olyNc87)qM)82*cM z;QI~G;ygHFA)Ssaf}}J(1#zJ zM|G%q+x4l5+n*xlGc&t&0EwM(9M!AW6nzJ)TJ-(QoS*(&O_;@9+23Jt(_I#K^UD8c zs^)2aJbXU?H2KGlQZp8#)QrtLF4>pf5jRwxJ#JDpPxCJn4~wYgnfZkjf=+hyWQfog z=4q;VoYSkPU*I_moju_TJfXBNozttl!DAI!V60+im8ad4-G-ODMQ-v8z$(bS z$#XWG6nt8IYd&q2ppV3h4Wm7|p|8I+p{sn4xcfVEy>|j)YZH9DrD%P>ktC*nZ(iza z4$_30Ovuejiw4~gia?rBH?x)4P15*N*xf!~bUVdMqvD2B^491lr_8>o20DM+Gbz6L zywwnj+RmUmM>D>|Tf(PZAT_QR*Zcs%qKkO>2lv8IQvGtsAFlKy?~6|VQ3_6X|0o5g z8-9uiPRy7qIPt!y=Vv7|x%WleQOzr4ru!3cu3RTmgUpl(hUwpeOlto@0moB6%g-LT zL7Eq8@r(1>!xfzF_|(&1T>PuNCKM$-9RkBjhxGIqc+T&nr%Av4iS%@9frTrgx1MD= zH$>Y9S!cWb3wGdd;dpX5N&_;aSU_kf@u3|{s}iPh~D}&?)c0V$-2DwQ=wbD zA9^2siQ<56@qTCvk0tMiQeu*7I8tMD>ddk4!e86?)HwYsIB@Uhg%h~kEBmsI?a=sM7Bm6XpaZ z0~}6pt;-3XSo6RA@aDnhR)JK`Zl9)q(2mwWDEzUOb0s_`qHr)K|8rCr6b|0>md8;z z=v4{_^Phmas!8JdSj)M<=RJKT!F55B=D}YOl-1P>YDp z!MR5~elf6>Mdr|Ly9YW4L)W&liuT8Y%k|-g`)!EfLNgs@1BAJ4*V>X;} zHIyWEc2y-?@_Jv#RLeQqo>-HGnN6*R=$5OYREziho=>&h`+h#>Xgh}Q$o7_V|2wIE zJsMT5hVF-3t%jb9jOTRmMte(M0PK)v@e=sCX%;Vm*QHy|w@j>tm}q1*ly1q@P`c%Q z(DXUy+ttWEiIMGBBYP%Bwoi_1pFHvIlPBJN^2EDOo_P1|6u}IOC*B{V6}1}5v`$+M zwZ}N-cs}(<esU)gBo8dTjp9kyPlV8@rL)I z+{obNOY(9V)WI3NH*~O)ID_2N(F*EUi`+cxzVxE;;nDi4J6gB9qxG7#|J$Q=ekZHD zT${L~^<54?Y72Eo>q+?S9|+XtkVXFA?_{;@=qM(Z)VzNZQ$#{6%|SR6)#WW23unwq zk=_|4nIyV*4v*W%fr!PV3`&Y)-a*fiQr@s@w&FP4Sb*H#S&rMcI$OMW+r3NFkp0;i zva7ntA-k`O#T#~`yINgM>eO3SV1-p#G1uIv_*a3&jf%2Di^Fn4p;bq<4G;B_!!pp@ zlDBRT_p!KODer4ZEmq_D%3;{L)ER~+%G_a?P%{L5SpM8TcxAdN;M3rBZ+q|-lmSGn-_0!AB`7pKOQKDWS2qi#oN@gWn@&tFlCUu zc>ByCIV4XGawpl;ASt98hSI_AESq{IVXhj6)T_s2s#!Mmnu&08mK93}%Mp1ut^36O z!E!_v4Ur>q;t)9^*A8(;bVREF3+TqqMP=WdBaI3Ij-Pzbk@DGH*ovd>>9H#$fj8&Y%qQBiN{B<3W zjjWeqg&r@4j
%m%b@E`XQOaS0r^iNBAq?oH=MaQ9r%JVeUP%Y*KK-?0AwnS%O( zk?t`6?{#Rd7$v9Y1EbVfj|l2{qvcqqpdPwxwDpA{w<{CfSARZ2rM4Z4zvfkx9@>Hn zTv=yLkTY~s@jXQtW2^#4d{6PD3>2fsSkTcV0$n`CV9%$RPuF7hGf|iOVNjl+xEvRvaTCJaOkvaXCiY`eHfdZ)BT(QR+GpD27}KUojv+7YKQ`5x*79zQWHZ5;vr`&`Z<=Bo337%` zkTZ0GoS_rs44tr3jGrcF=oPe33(>dp+n#Bib~}G7cvS{&=idNMCz-^5yq$mQOvxnv z!|nV7GbEGHl_aii=V$E_qt9}ggu05KbrwpOay1`i7-(igC0@!ke}`MMvMR)?vm}#v zlGc6VowFp97&KEdiMcZ+lX!5Z!z6GC-;u>}2Y+}9n8aoHOXeMX?klJ}_`X?^No<+r zG6~$le+Y5|r}KZ#a;EdM&wbs`ryg$u^nVVhVz+e%7#8qn4mP)G$>M_ilf z*%8O2duSc@h+RbQchOh5=-w{+HSrbEM_lw1E_#TA&ih38&b8VHOMqS^lRO22&hzo{ zdp8Hk{a`g+HUOE1l(kMrz+UuwUnjfKp^r|9|jYD_uy_3 zggpqo{c=73z4j8h;Cj$RNL6?nqH{ zF1J<;`3x*33rXq?_d_DiJqhnNI=+EpCmqno>E#Eb+#liKJ4m^|!og>Ray^x}m;*)a%)VepKJV233* z__1yx5)aaHrKZG-|bVZ%jdS z!IEvXX+s+}yDOKs}rZMk-)L)3Q}Lb$M(5 zltLsh(k)AD#}ri-R+w9zs4ll)h#Fhak%)0qFI+4W<*Jp{8ebPlOV*RP@D8i(jIl^k zZ>=Lq9Pp1+o>O(>o7UEZd^B^oh^zyg*e{gjnq<*|HpCq!R-#*n=pR$WtADi$1nMv| z^z`-C-}TVcJFI?snwuNhDubfx7C{D!=>k*ikZ{&m8$+Aa4Xc&)h~P|h`0uM~M0D*` zMVCFQUY%k#tyNVCV^jyLj--XEZCWL@;hIK8*PUMWF--s%4r4>;P*zMZs=R zvW1#Htq+W7Qb;skRcQJ>R!9%Br;tamqhzzhE&vhdq@%k;yt(W>U@@{2VU%=?qDF*y zkkKpX@R-v{BtcMMoS=AH7 z(EV0s90HcB^u)BAt)x)%*Q_HgO^>$F8#;OnBSp;r!ip6ie_)*@GT*nFK~eLfV57Jx z#%?c~zYol+4=o@6p7XvDuX&Hah)3Jn?ZosryIJtcHkx-OjIPzt`pj|C%1h9^hBp5* zObE{J>8AL2g>M7L9}<&7*QymBP8HP)i0TlNiqYz59})V;R;up^obM8>)zSJ0#-lBY zV{S~ub-g(FvDH&-{TPK>_OUhGA~0Ue|HNvvWFmCl7u*GMC+RVfq{pbF6I)}(g0VFN znty$b_&(>&LkQ(pbZIV~u8mbBa4KvDus9WhoQ@|p5fQ*Cu|fPpq?L*2+L%b-a27fM zixuSWl2mYnQt1#>0OQdL8fn+TMAc&zywxxU4)Qg+VS?HiKo~y*sfeb+Kl3z7Z7u){ zP9tP~Po7TrGXNUO7#-t!z&61kJ0|N-RsmX=<;U+9pw_}fXHDAzz~eB{@put1?zFgf zfM(C>fmz>goEG?J^kxrW$ONrK7?JR~byXcZWQo)NX!U}L(H1Vp&(laxe;2Ux=il^3 zdd9$*8ctJ(tBg?;!C+|68WZ~BbL&OJ>uW1PzR=Dutx7Yv6{vlZs+v}tL}J73N9;j~ zt)X>PI>*!c#DUT}?m%f_*B;&CVr{XO)kychB&vqik5MQasWg`<1#4(KsXF}+b>gT*3n{gtl^qQy8hxIXk8aZ(6t)I*5=D9p!;SRG%u5VP&(^qF;zxZToZ0DraVbf z)Y5YD6)rWSUMI2R#hG7Qg`)CXYlJumMi_!C&rWGbk>#M(2os|%jxEZ$2<;G>|D)AY z_u{E_=3`0dk)N4|5vF&e z6K12hUblUr>vX$P_nyp<@th33=CL=JV(Eug^U&%T`%YbNC-R%wujt>1Uz_1+;{#%7 zbNdPC%d1n3X=oQ!i`Auekr)zdSBQ17b|>*xteus1)F*k)L!H6)6!Bre2p0!i+Zp01 z&KL8)w7g<)oPDl$B@mn#L@3T4qF*O|i?auN$4FrHn9#@;c4xg=3A`Td!uS%gyrtb$ zFA)#7w3FfqMJ=dQT8cMX+FANG@qJ7Cv4ov|iKMj)#-lAT#iOn4tNsWPDvP&Q*!s56 z?sj%_J=nnsN(&por&Xy92r-7XaCW02iOL1vNF~^#&5xtq6-L);Y4woch4WR0qewN9 z7Qh(Vzq0gjkrYKZF-C#J#IR(0p!cCH>3K-pnrwIS@_j_qCg+$Lm>rPOQdt0%5DL?Gbh~ZR6c@&xOWb@Iq!PL|-9AIdTWz0Y*j2EKGwm~jM{a8}r^UA?nvNwByeA22XgRcF6>SusixAe5kTL1nL{*Ci z!_i2r6V1e9L4f(tLNo0W?IJDhQm}*t@Gfc!`h6s)=VhKuZ34qO35VJ5X$5o$$0@>~ zu7w*ql0_LivjwR{QAPNjxG^ihblaG5Hv|rRnr1C2n|!0X>o~u zsQJhISy?$ECoAr^-&!s2nx|{+62cAECL9^Qn>fFGfSe@94ulixpxDM{IEcbWGtqJo zkr)HUi6n@_>&W_G81w*IE2VP`EhyC|losD!aQX#ZJ0xNZt)0?YO>36}rNv5b+Ku>@ z#1t4yTcq{MX{2*H4C=p*_WTG+m2WLT>mBeV2tnsY7zCijv=J9EDga(&@cs;gEYtFU zqG=vXKyXct1hksN%xg*!4^WCjL8}O+DM2bAT^$0IEI~Pv5YJUK(v=TmYjKc%v~cD! z0P}SayDID+TvMc!P=)zS7-WXla+sz`kzlGMsG&sy;VZ@3VplKQ&p7;?W=*j%$6gVn zV(|fzxSG}^=?qIsR1j`DSXyz8lUAN|HX%Ia^bcC`z#7_xW+NSKB&pkPG>vh7CrN9+ z>lk$6X8~%%MW#maJ(8lD)_%uHi(#Yq6$y7pPz|jYU}UOvyy1AfjdU=a#HhMw$fseN zVXC3Mr=xhKxt$!U>tG-C1m8uD9R;w9)&?8t`azbVj+R#{$|OQXcJg=R-#O%pU?03M z!5C310;&5o4sk^fvuz-HJdc&4E&NPtq*B(WVbFC|R1QTn0hO;t5zxC6COXi_m!mKk479pJ@rW}R=qiB$g4U=o zLY0;wb0k3xEfun+v1jcw@b`yl?Fi0= zY2W8A*1pee|Gm~o@KBfpklQvE7SYHcF-{J`1B~hoUxPt;Xi+av(@{@?Lz19|mLiBW z#}Pn}!o+F|!Adi-jb=ZmHWKgwOl$3;Hn(`1|MpudP-1jf+m0vr6Bu+FT6vlAxLv>6?~=1oe`jhL$35V+bOd z=>X4@6xFmCplK8&m>~&jXeok7Ca5qG8$YZ}T2o<~#z2Be4uL8e^(Q{w4P66)9*6q_ z7$*>2sSYtMhHV;~RJ{lybf^MYiXf7oDnOr?1mhXmCoq@>wB_FTM!JtHe_VX9ksijN zb~cc|27sV23!v~=c5+LOGk>+t>^=o!qa~`dSL-Un63Hy5!ziRG??wb*K)1L@;6$mQ zc`H2jNO4-S_X4y<2CAX84F-v<#rH(#Hx$YXC%_<5T0cwYSXw4Xo7UPQKvzqGF!LML z74`1~3J(mbZ(J+M!mCPp|6|l7cuwjY}eOJJa4gL%@IqjgV5Y<3ypLC9;bTtEs0B{csq9ZPNTGT|Zk?61ty3`Hf(MlT`gdylwRYTQ` zjFHt9!AGi&iVc5(K?!M5+nrN$bOqB2C5G0T9as~*u_-BaX zM;Mfb7UP#iXVkl7%wrj9j|>&=6eoanLX8WmVA#=Et=rj&3^@xyAk#-ehUI$o02(3&8f<7rKTF|>;#OD;y? zBrqY8KzNlxEsamZpbnX|Q|NG2T?fo<5*zO5Hx^>;;Di{@5F25@OYRK^4lg>^ARyH^ zq9ZQ?_7X`L9*bLnVKg4CS0m#g3EirPC_Lg;XvMOEpoyTXiJmDVucoyC2JNXg(!p5K zhkhSvO(fE=M8Y^9msu)kr0tZlHbUuE0@D9u(mIktu^Wp_%gM^ZU{qGZEs}I< zr0%Awj7G43P_scTf}X;_TVy;_XzhYAw556@9ZqZFaE9}XgsO=o87@7st6|vHXgis! zj!=ecG5E)%wIqEU2J;9lCo9-Ph-4+)i#SZ!8>58r2LRdz!}OnqP0g2Raavh0hIWbG zNJmaFn0S*O&X7)I;Z;B7im@ercT{|TrJT4 z{SUtafac3U;h|m%uanmJNR;6LF&o&`FxXj3rhO|+oOYomcOum=?i@Z3hox+iU4KX$quBI^(u11AZRp!*#1duz4k0Y%Uak%nkhOy%#*l^`72X-9{ zh88WP97ILdCz5oZ1E3Yq&KAV`z3hSKQTf-CFsN%<+hLp(>Eab)AXMV} z;C&v())rz}nbt`6OOm9H)w;hS=#6JC@d580>9THqx;O#?&s_r8Uw;%#;GvA1128sCJAXhHxt}s8K!Fbxna%x7QlL znhXu5*Y$MZVW^S#5(cTzVveJ#kJ#f9TSJRjwq~UL4+jBu!q=+sq=@X;Q1jGxGKz4! zGuDq_n&ghkvA%_gDw`IM^xDBh!>E?(br@urR^K=9=kzeT4mlXr!y?2rBv!OFjgnTp z+t>amNF`I3I>BfyfpOwfku3f*0_t}f1%oWns)li5psUtF(3%uRsHpRLfYntv6toyq z)5J>w`HuvrsOCn-P(!N&48E7(hKchd`d1k68d}sEgJiqZ2t&4Jo?rnBb#Jq z>S%o@os(5Ts0r#u2?}>Ss*NHjx<3V}Yw7T5Kq_WB2GgX6GB*oO2SP8tw>u1~ixyOL z!x^rd2)0IH*}ReQ)1x~WNVyZ9R)6UnI~Dj%jvmZ$-V!J-Q^4*n^p!8G{& zFvumXEEuPoWpzh<(C}Dc?+sGD(2Fo2qD2)uP5UAVwn>5-TH9f8szsx%h$AI?0nq;# z+gcFZ3xninZ5A#2;e5+xI3IAJw3uYmOe_Zk`fnMG)@{EdSo3EDI8*1H1cOP9Ry|C3 z#8CbtevHJ|(V77xhYTGg#?r9Kh#~zP801LxJyyqS4v5yT(i!d*5o}Ea>ohder&^+q zWQcI%M?m37j)UTxrc@D7n2MT+u5d;(tu4~|2iO`H8$>C>sa_50TV#ko0EHu=BBG5= zsUn~-6?K!u!$eim32^pPFi{{)9H_AKL}Q|z==@Djuv=t5j&NzcNjTOAE5~uFx^4+? znpiTx&K|HIgqp;L`Oh0+P?#}%1JHLcO-2$GN1TM=QLApD76a`VJxDbQqhLH*ahN?; z!aooOoo6Vl;f|9QDWgQES@6z*@o0tNzzSw)&3+04NkrWT9<8V;EEzyh{u+joifRy; z$DZQo`?wbK!ytRC{*@R#*e-*0!(e+ftak?6Nr^xAWp=_c=U4FlEWAVPPQgAEU>Y#s zQ~hBLmd;vQRWLlKM!N>a(&Dbg0a`j6U}CUbX|7>wSXKRNxKMBi1~DCh^?`KO()t|6 z4NYeU75bQw8rj0X7nlcNkj*Wyo^+hFo`G?LtF)E?RPRt+0qZ))Noy6%X~d%ds&y#F z!J6tgX`NL*>37swfOl|6I>Rb*oV0qvoEG(WxHN&+>zL_ZVc8Bbt=Mw$m!Y=5El=&K zUGEca_7{m~huSH1OK{J^l%NwJiie8_qDah>P>I-;aT>oNmAkxpKH@9f$?aI z`>S~JM3-T9x1{803cyn}jDW{!W{3-h*_Y#{*4M-A`}B*&?ZfT&^asVIBkV?fzeuUF zFVLrozf|FH%1$wHq#e-j5q}wJpM#@}UyrmaaJ8#&l-)LXnCZH|nXoz@ds|OCaPUkB#FJSkDRe2P4kPd!cYX_Sj;%M`W9qnGO z4X6C=!@oxxGf|a{lVLt!oTf?7S)TE6BKN`O+*bsfKf)=Quub`+A7W0>+XoIxTercc z0Lus=D$BN_h|C(G*v>}g3>O_CMg9(e^T!Ce*rxZgrcV;hebVbu`?5scvqif$gv_4s~sHZA@J@Q#aH~ zz<(EkZnOBQ)=qCF2C0bT6%x@n#m;6gl0UMq6Y;lAuv6I)r&bHdev=09Fp8 zj3KF)!I!{Y52KE!D)_a4t%kV;=5ZLFPmOP*O$!Gk!Ah5ahg4NSa#3=nJp^U3dN$nR;$?`fP9DNf6(7M=pQJl28+$qUl87Di#|CQny>Wvh}BM_x}up03~z z!2LAL4jA%o1t$%8KFz%_!SFl+&kd*mi{R!ysoIWJaP`e9 zuNX5PjDo9=NrXKg1?N|whhWr48{+vnNQNT=p=T+K`a;1k3DFU-x;PEea5s^L(;y9J zK^o3}s;TIfUxZN$88Dm)ISbP8YdvQ|&Vn>SPJ=W&Y{03I(;yA2h*KeJgi|4>K^kU^ zQ{hq9a2BND=@QO_8JxvncwmJyAy2lb8shSBCd_OYE(Za380dBI+z7J;ZO+f{WOP( zhv8O_f>VWgJ`DGqIL#_JRjW^j;YJv@#}xcFxbKD848xVBf**nVD9kZ#4sxSUA^2(m z_b-RSa2}3^a|cvyWhyv@iFz0c6RbH36BHz9SYtG-A=NjeFo7CS{vbC^xQ{|%f>lFd zg1cT6CRjq6NiY;9STYI|&KlX_DikK1Ek(yqVS<7L4GTc?8H`F$Wt=d`4Ws$zrJhZx zYm)*53ijTrg^U6s4 zPvg>=NBapvok#zvWeZK$_0Sn-+5a|!lzEI@0CdnireWvH|6xTQ10W3=6Y(>SXnH|W zmq4IPZij$zNq%-=S&4CJ{>Tx_3%eAqSdkq#*Jv@kpeQ}yH_q@G@xCR2%!&Rpp=0UY}p)hwll!6uy`1^Toz_c6Ry%fL7`G0R6K* z-)LD1?+WR?BADMu9OXJuMwP zr846|TW>q6Yx|Cd&sSz_yzC=maX!je9k?iaM4oYpuY6dxxa9)7i+*-!*9ErUYDtmJ z=%ptYbj`|`y+VAs$nG6ej;`a;hKmcYvtHPLl>~Cj10#&seBzL z(D(uhYK$fM`ThM-#9b9}{s{5m61!(RRLe?>)%fj_d_Sx4IxFAf3FTa7r|O2^?-%`+ z+Bu1U|LP&tie>q5|AGhDJYwEb`&10752Z;Bp)?N~q2$Z$`#h$n(sh$c*o15qG_v#Aul>Zd+q_EkG|u z56Sjd1x5wBsjA(cimJWc&{K?7rN)K6GAG0=TH>E;>~>@Gayl2K<)n4=XJmEERH4lF z2zA2H{}3q$>LF84YM(nL&^gzmJB=v8|8&4&!p(MiF+20qK{mki+APQIY3BA`CUBdj zw;O|`%K`zv%vWolXuR3(7Sk>#Es&j_End6XzRe6|1_ENvEq11zZ@j4GUnN%EVyDMv zW)@`n%c}wbqxlu*feVOdZn1yWt3yxUYJcuAa?w-W~Lr zrg6kW`09FJvC+n7EXe0L+FPIRi3z3LW7nH8jo3}{Xz#Nlri!wA><*!K@3;3`zWnkL zBhXe=S!gXiV-(x03;$$4?1myd|A@UHW~dDPb~yB`C+FDH^pMYp*`tS!J!aQ?x&{0h zcQF#<8vYIApX>p$d(JHKXM5t&PX@@b`dBz3nT_p6=!&Q9-MU8&6p}%Cmoo zGo|ZlYm!_s2VXlFwqn1z`33> zR(bSWfJmp68d z?~&2xz~G-jqdZq%+SNGMXQbx`j206D#>mnE`vVu9F|n(0b-mB{5!~Nn>@~<{_ALcT zLcVc+zLDTF=CN~@ftMP4bsy)GEXDM>rZcXzbT)_%mf@FpmQ`V6$N2-l zu>C#KJ&YS*dCdPKT~Ex&DhrG@nq2`Vj}}Om^C<9KR~oC|qG0S9x@we}unV zpg>ijb{*9x ztGH)znJ7JIr{{5zX*{j#s=c|`H1|reMO_TlOm(b-0?HN`}F072(Aw%@a zO)Jb6U%zR0@54owu@_wgl1q2YCG+b+KB9L}i)Ii24!{D)A#m;w4vHd^Hy z2bYvqqR;G>edgJv9Po~N_fqzyXASa>zb!2_9<)lqU%RIlW&{F(oDLPn#^8i<x>8x$W8=!oJZ&5_SBl234Q$|16fA%(&E_&agH%(wH$e5LAvd)$WAZpQlS_H*TBZt z9>!Bu>XuPE9oPsX)<@&P&xw4y)W$j)nC8K8zpZNMc zyIqjWOXIkvw?oh8eDj%<;%*23faen{JP5e_G?rsT$r>7N2MYbF8Mz`gZr1fwgxCrp zOgCO%;wuYu%Yy#_t5gjmE?A9sb-mJPfytHwZDFY?<{h*9wc^^`$aOG?q zFmy`0SIfctW80UGW29%_e-%iw9F?92*BSw;fmqH z+t_Wo6%#NP4i_Ciu*+L=0d9P4>M4b+OtI(#RLWto@dI3>P8KIVunP-N_<}1b9LchO zv1|g$u?|9nX?y|!8}hNIN!d4xst@fnPq(blc^}$qtkztqV=WM#Ay0^wpW7)(T(5J* zhsyX=)7APZPLzKR*=Kj?{Lk&Tjn-W48h-;?clvmm82_bx1tuteiNB;nzs#&|0XU4w z!{Ikt=ktGVzESQ|?Z6eX@rFk?Eu&Aqk>WFLV>!ek%lH)Yt8Ls~Un;Us+PU7&nT1@c zVE_1}-ADI|>reh4U0n@uRMi#Ux0~G)5Mq`PXfPpJegtYDS(Sq)8)f0~71m{ehT7dgr zFf!p#X2t^F!E3h`q=qKR9X!Ev5wpRTXdZ4pEX;XR=KOMM!%3M0pT(0tf&U9`@1Ame zD{0KF$_q>l-Wm)pxFMG3$irSA{e90A?eIyCldXUB$w+6G{u7Ch9>3>1ea9!mg z4yz=yoz&Y!?)K61_q?t1MDXrAk)cjoEHzb5d!2K!_(1vA6Z@B6j(B{lt11_kFOKcZ zluD2M{LcA#GlD^_9pw(|Z?fcSy!QXOEcuhBWXbihJBG>QL;4p#xVn1Ds){8QvtxfQ zlwnTntDuYy=%HfCMBlnxA8D{yGVr0k_HR8Y7@4X|56T23Au~y+sE z5*gDkv9F85MX{{;@(-UgUHzppRKL7WQo4V?ssC+hsiBST&~wgxvAase=cG?h8xY#) z32mZmdfM2#VoMiDwZ}W>XebRIc>IM7jeWgH5Slox&E+zR4Y?t+2sS1!jayc)<5il8 z9bRo-C>dVD7WJ3QH9=aU+&SXqQA`^&vEQ4-v_QFuX0)X10u;kr2iBG20*~sBa=F2& z)6R0)GCPF$&5X3Mp^XyS+UyBE#a6qY=^skVo_-beAXwA06+F{iYO)S; zXY^nN>KLmhm`u^nDx|1B1!Bx1U zU+SDylIzaCRqtFS!`-uz>6&D^yF0~fc@f$0v<<96(x&69Fpr$m4OMs`2I#>m8RN}I zd^Ej2K1{!=!t~l0^H)pM?X1=M2c#hSXo?A*x?MZbwpw6LW^VlBQ(tHC?ZEZGyaw`k z50eT7t94_&#u>RbY{~w}Gsn!ouGIF9EKw@*lQ% z=09#>HaJggeZ`o}EdeuRr}kz@;Qqas3TIiEJWdQG!`t0GQlkDf^0q%|QZM!;#_RW5 z^ALtLK6%trFY^`k!6kigg@sv9wS`%Jt%b>dWMT3bEDYX_=R5qc910fo>`k~`r?B`D z^YL<$k57rk{|9`D2G&Y$Sw2h(yZBnFehX)6{KUU z!tl&bJIP?`%flXm!Qih?9Go)(W?1>-42c7EHlM9s>tvySt<}d_uw2$^*?P>5W3?X1 zMD7%rLcc~U=L45QU?xBsV}^emd^_;s*f;C3Ci&|u&1b;X#ljopklTN_kNj}Vc@#B< zKY<+CdhR~4(LKrIa(!y?w*jBCFfaIAtfp4JNQs^fcdtQa6kV|NWMFY3rk!Eq6~SOVxz(5 z0B?rC@U+hjKM8y*FilRwGvsM_cF?C5Mzf-cqndVx{QTYmY&XM@HqX}v7)+kFzl|Az zG?*1mnb3=wpH6|{(|E*$UO}&*`wXa!=@r2V(fq6wn1R0%E!# zHlC#ZXQe8Fxv59oigpo?LSkmZQ5Js)JTWbI!xvgSEJ;_Pc0P*{NQcI*jZTb>>BQKW zPK=Ei6tpoTfi|XBV`F+X7LF#4$XbHLQCS<)xv?>w8yhqDW@CCeHs+}p8}sx_FUC@Y zucbXN1!eSpdga~TkHNgp-}m9^4cUCEg?Sr!SjOfDYdxw7(_1p)PjDNufVps*;l;xz zhG(@KEljm7>eR_xf01=JFG5X`metAg{t8Px7zROwI`#6lb67j-aj$!it8`mGgAtrE zbx}8ut{BX^Ll!2_BP}-1&ovlKo`EleS)QMIFc|z|7o%ZDzzqCyguzt6voQvf&qt)p zVDgNd8BCtvv@n=_n|8hcYXnx^mV}cSWRkCCTi`%W(OM>@+KePhd&HEarYY94PRwQB z=8yKlv{P*UOdrgzciMcZh0A@o+g%#oisrnpWk~$vGP;jK4+7JS`!-(dw@QJx6*qsg z9@~mgPOElpMabn%4K^U&6NHbF5Bh5S0=^RW<2ep2C zq8T0A(E$talrm&Nb~V^D+C}yc8h8m8Fiyir{FyML`DZ4~^ffZ=)0&qMfat=Eir`2> zd@Vi^aZKAG#+N z*#rtWXgwcORvpJsyNrvSki=gAZ_uutl99t>@60j;(Zs#(?jbM&I1l)g26mw#H)~`U z)W4}UyP$r7wi6B1&RtUF%|b2tI&(KVHJ~-SLG07|-MHTaF%WRU3EeB;nHXtwG%ZC({*91-vB!wO`z*T zd<1xt*6u;jc(XR_K{WS-cJ4t1t?KNRzxpp@446)N6H&(-HNF>jdN!Wo{G^IB1pd}( zqy-gD)S4EQJ)zAl7)|}uX~oRct{trq?$fSTH0EA}2&$7Mx4@2>Eocm8H#TN3aJ>d! zhNdQsyo^F#ttD#KW+wf#gGrXgnS7(pE9jsr=pfT??`FDODEW%aK=`ZS6?p~&JJ1F_ zS2WUw?mDHNZ73PhE+!rL6f1^Y8r}~bwOU3L(0ZcxwVmi}EWTfU z7>3U-#s4Bh{TNkP$1$OzHASP)8z2$5iXbTN3J8k0;dW7QnJAheK=OX8&zunNz0dP|-}m$W^?sh=b8@<>yQ{jZ ztE;Q)^f|11IQrF%(d(>y@$vPsv61%|E6O@t9t!;!{^1wTaVgey>uaOg>GjL-XV2r) z+Pn9%DCT~+*1PXhao@rJem(wB8cXs2p`T**?~l^B8gM=I&?79Hy^g=dEa{z1gorq#fVy!r7%zNfXceDb>b&Yc;pM*G=={uSGb!cMU4ZABr6jrPLdSLGNE zv+mSG?sQ)1vPW_5cPY;G*A?fT*Q|EM*?2{9zTmoYL5ct6g28_2f^xVFWtrl!+uWo$ zf4aK8*{Y5%8eM2Ul@zSJ}JS z#TN!<&C9s{ZnN2Vs3`GpKl`NCyRJU36xx&RhD)mz#o2O=O8?`Mx5w6!Nv-!?eWls# zmtL~7q%-L70FtU``UDvYWCf8UFDTha(i48`@ytz9D z4(YU?oP{GQMh+4uj4a2qqJmpP8Wrav(Z$3TtAo-i#Qi3gn0)k)cT7kB7?L%N?e{4D z>--Xa(bt@B&$P2%Wfv8nJ9g5Li z)9PU#y@yf{w|X`+PbIPWWUBocyV7HFg}A`txHS%SqObP1iz8;%HIQ#r5~3Q1S3F~% zSd(h+iF$?NCo_vMZ`DM4MRf6G-OQi6%vRGSFIA*^viQM$%MDwf9l>&cyYRNPy=C2X zqg_cwOcOnRB({8ww$#a&*L zT37#`JjiAj+dSE5v*Mh1)vMXyC9Zk0)a1@1omHTi2V=yC;>tmKBkmzPl{ga2lo&D0 zi=|2-A-&Rz-7Z_|b;+y>lQ**lD9)Z&3^88oyml(iHkY~CU>5n_EIiYtb# zF?|A32K;sQdG^FGSDaHhe9}WPU%}O2R?JPf>(_O_zjy)mRLqsQJ8(TuFv`5?z7OzL z%$MBtRv^9oZl3wC^P6nJtC%=t5FgaKl*nnMO!mrRB_8BDQM0(I z8Qj!T>?cYMiN=$j6)RlII>mbEN9R2(ho^pbvg&ecBXg!oK7{Se$7bK>Q4zM#qhh!# zwji$l%LZeGm;E_Avs>-9S8Ga@!+L|LpROk6tiI+s*mHq|~7w^9z_WO8nM^bq{kk#aF}+4zKUAYHIz)D`xAlKfFz^6;)jfEEcK0thdRh zg!S{bi(7nIFaN`eMHz2^2rU)kRu%rvnAqpb3P$8Zm}rWkUzR2%ZbOlJ;{EY&j9}SU zF2HIjwx*J(pexMJ+g`J0!xd%dT}7;!G1JMggMh3{!)%9G?_Vz{$t@=>b{ooz5uQc|2luBFunmYs2}vz~Gp@{65ZJ&HSXe(&-flt}s4DbJ^ja(xEHx%0OdRbBoj z+q*_RK|NNS6JE(b^mDReO)ON*1x0?!2)ZXI)+eQ$yfH@Ja*VvNj2P`cCp@hcN=%47 zB(}Zf$#!E64VXr#7YNBg6EPMR$!f#^3+urKi)j{?V$Ey+?GNJ$wPNgyEz`AsTc@{O zAUkSng36bOy%v^kSejB)Bfht=97n;BKX1*b|G6QxF2*C|M3B?$=W`emv3~1OcDTT4 zRd&dGfl^EN%S+vMw!P&{yJl6tHF}=WY;V@ z#}s_#Yu9FpwVM3S+zXpL)EDCW`HGTgJ7Kyie;!h6tWxD zdLJ-9H@tdb>E6V}0?3l?h+XMsn1%k1`ynolo~EEnPmY_bfdQHyIeGzTflMkNj{ zo9#15!FU;(^MUcI@ESxojL8+xitna+R>a-x6En=pcOUxEQlKO`CmtYT&*8cP-{ZMN z#i}e+3Y2gDGczerR*LO6el)+LXe_=&Et=I$ z{_yq5AU+wy13>(#OD1!B%i8Nj_Jg74>)TsagLqL%UF{AxZ5W$nRBMT(ZE5l;Nkep9isG!?9Zb5)m5=#ING>V77yu6^^bf*ncHtWNEU-8SJz~x3~Nu zp6be`IRfrwarYGj7WtfH&ls8qE6lm3{j_Ui3ELX8h}*68iu2+XzT0vr2!;oCL4kqI zrnEQGgK_`PjidCJNK@X|ugP+ml>Q89%6m~OmqqDkkUrts7@yx1m{1?O(2!)bvlGmk ze~2ySNv$UX7LC7`S=SX93ND{CLa~_hHnFE0%NV5AC~?I#D{79_u@5~5YL!4&kDAIZ`3e`KjUU6*|om?*k;(>c<4Ei6v8r0>f9r)jX`2! z2n#V-BUyKGdk7oseeOCH?Y;ob6emO2w0wUw&|nWcNsa4vGIWtHG5?cF^I&75ojK#% zNAF?JP-;fo4cUptP?j9t-m;_ZYW=u|@cO|yfqSedGqR06L-%6Q6p8^Dc-@L&-3?!m z#wGs{8CT{kIKbl6M(VE8Y~xDvP*&tJ^jTf>ac%2Kby@MU#?t&IgIzNRO7}vP@=>W| zvCA-SL($cf#Gt^%Q6EUFR%M&ZPWIrpQSb03HsO7H!?o^^k+;empF z#RHecVYHs8nOx(1l{r7|DB~f^Op#@bC{uT%P{lvth{jo(sNV+rcGoJ~QrBu+_t~h& z=pp1_bIalC$(61~8})LoYjS;feH=uq#E?-5DWzqoxSlTzuV3oA-)f8%i^Ewyn4g^Mv*CSZJoXOL8+>U8KOj~_nqiea1r8q7(zPJw!p_S-m z;O?^4)^BvJv{mBo3QO@t9%r?StVot_Ug^58CcIva5%rNQKh58{)Q`yeG2au+ImN{i zO(%Gw<8s7{=@pZwZJ##nLK^N*O`CjyIZMR{ku1g|_UbGEf#OdB{%Rcu;DU&ZV#7VZ zz|1|3>#SH5#pW2p?4fq6XpUmxo_DlrotYtmquC74LN}Nx?u};M4eH$G^u1tY&ykNG)`0Zd=P62cN?tX=|#8xM#P~?lstQBCf%!ob41hSy{SIVQosovidFc z>tPSYIx8zzV{1l;FRg4~P_fIB%41cRIaR@5kJKH_A&SV0VRswG)P}&xj$tKXVHHPf z#!nBc2($B~VXmM_`GcIIiY|Qia2QM4e0W1dNQqYJLGfKID;&8S&cGC0@o;Y%o3`v` z&ztOKdlF`Z;(W-JXm4vVv>n-795GJ0`^OL^u2GGf41MG|q4slo*A*F>xq+PxgAutn z-r(Y?1{c&QyICxXV{^Km#~>L%ntYG^CZ9^5!CeL=+XatjS!p)l`{Am<)rhHUws!%m z<=2nzg`VW73%w79*c%UJp&@N8lSFMi3wGRcJ!R1Gy@{|6U$>k0sCj?wO@tHF-f|X@ z1<>U5E@!`X-M$cslw3f)LwD42g{0zt1rgF6j#GbJSBErk#f>@s3bz!TkSGT5&?_aXp9<0|fSIz9I2)UzQ zlEj8sPZTTWnq0-IUs!2vwk9R^k@^#^bp`%*@pBUEoBx$7sGut1v`aZMK&`r17&4V| zty2ejeSFH5lh3S5D{GFsh@g!tCj`F7+Sgo`n&&PVRZ)}7!UCSgzV%`ISeN1OQJ1p& zV6(wb+@H*nz55=9X9AzFt>qQ*dNK>_zo*@!;tkh2n+bn6+TccHDOLr}T1b&%-YwIH zf_S9Wg)F79$!MQ&a!>^|b92#{lcg1+YYNLB;u|y7+Sby1HNWD!ntaev@|8IJ?SCXL zt_ItInySl&z#Wsb8J| zef|h6e!8T*0ffHcYx_qVW83evCDkNFH#57x3L1#C$1dyPwcj_{L+~X&o)FAG#d=|nYHQ}=xAwMOSeNxy8pQ| zP>wAgQHSYH{dg1iGuSc4!Iyax_qLYo>)A$rhV(R6WM;B~hOPBi_KMpxSuFcmJd(*W z951x(Qq?mIzCwG;&bApybD4gkEdyy)rnj~I$kj6jncmd)4AMrKUe`7qX_HK^Zc9Ph zL#9`@{l?TYW|>~n)~FUVzq9lw5A_T!;_WS-?YofHII52J82~hv*V{6X)>yW*{c6%# zHn;6WT4Q;stpRC`a+bEYeDd09*Sd93Z8H?z3+}3I zYyG6wRV}X+wO_7&(eqMi;Kwc{NxYlI(%C2CN*0S_OGRWhD-Jdv_NwSQIxh&_y`&tVa_7S^)bqczLxj@Hd`GS=3z6?+G@p{M~dhLcC@ zz4lPNBP6o1RBZ^YIa<%Mj@BG)2rOCNpw@0Eia%UDU9DAO+FItmMy_!e`*-zy_S7{5 zMh4XHs0%Flt`2MRp}5<#57InnYpE8^IV{ppjH)6am*pFF)FCw_mz9~mo4)gs(OYcG zWg!7@bG_FWT{*d9dO>zU-j2G0TyZ>?#g5u=ZO8O+B@;__)J-V40L6vPmmO2D8e)#s z!k4c*R;QwS2Dw3dqo$~q*Dk9y)D_hgPbUAAPd{2yG@YyX>7MaB>br&GoMvCCcUa0 zK20tt766KyC~B+GNq38Ke&mPGy_pYu+E1>k=)qsRmad!HfGC3pDeh+ot0zp~RsU%C zrlQD?5&Q7kRUbF~jLT;raDyw!&#B_4x+aO{sE+2fezAEi$7UUzX@Mwqo2M78_PG zwj#7z!05q%h&=&Z15N^ID)FnDE*ht*Vyd-}2%$H4M)bpy-8 zYJsLAH3j8?cK`Z&)oW+`>kFMrnSV`K{VC(MGyTf@588sBjh!4i`SCxG#8mV;H~Hbo zW2f{g55sk?j>zsD7FJ`c2&?DL#9@1z6DM6c=?O_diE6_j8D-eHDYikj^0296rf!*< zQ63Wm+9JCj+v{ODuV8y@5kL2132eL=(4Pg1#Qv-+vr{^S*)-HrLWODR=O}Fu$NICW z?4(E{_3JHnx~{hjx_Z4O2I)VpwzuS7r!t7Lyh1a8_2MP#ir7g6 zR1aBPY=2|{8^zcyVqPI0f*laA7qS)pL!s>T*_zwN(8*vivWS(6nqt-~WGM$iQFh^n z$)>coOR&*H6c)2d!dA>i>~Y?5ep5U*#}CCGWB{^<8Wd%mJFRS@@@54n<$ZYO>%R#R zCGmV|aUKx0Q)}xQ6qbslv3S<(xl|4vfXOH*W1-7;g!g5VJF0bM4rN{8rye@bWI>m(fa} zE{}@!GmSB#Ac@0+5}6~6p}cE_SeeAlVmVy z5Z);~hB?LSBaGSXPf?q~vstTnD211^G2(m*5A_YDYH@UgW=NNlOL}&AgP=AOqpt`IJ0)6H($TDCUr9;dU z#ENX*o6QxkW%EfaT14gW(NOROIlNDIFGx11RyN)|)CcK0O5^Fxb*MtnKW{R@|c((6f;2he>O2g5PE`=hrfY0S$t72^dKRtFB zxTZb;F|)5}{!hh~b_HW|E<#b#0VqYdQs<*1>{lwVkiez*qk;cGD#HxXYhdaN7&k3> zL>wyQ-5s}3(QWf16(!k=iitKT*?AysjkQx0w%HGw$1n=X_u&tF_z&d9B9(duYRk3~ z$6^9y10*ZOB62$YSGg@4HbEcl)@Ntd79v0p{SYq=u5DrxNacDspS48)}zOmK*Ah)@9$CSW=0 zJhTY`$hKjN&C*NyBK@Q+;EKbbW*AD~MkBAa(bI|%>lIw?&)(-=%A11ke7^znV zGv)UswJ=OTgFTWDQZgB(JW^yb2#xhfmt}(?JdX^G4D`k$i?Bu;nrxsI$LwBlP&dSL z&0|2Dw~NKzMsKVmpO&~+A9JVG$3Ux(xzp<7sjogSHt}v^*g(vk60vBYT!KCws4qdD z9ZOKAT`ocAUgl9^rClyT&2}D6OVHsi#(ZHfBI`m;F4`UVk ze=6m61I*3ipL4SNFAdi0zNMQnK`bA_2ZXjmNS1D_7^7s^33>2Wry}W*<}J<*;s3-6 z@KBYu0yI{;SAf9k=#CX2a2Ta&1vp(TR{+0Ze353bt(w6$JSa8|>oC|`G4FJP{WQ|L z!9I$qry1;9$yU!AE^YPR;nG%b8*#%{6FaiiCq{6$t)A^G&9qfF(_;Nd9uh5$vQ-*o zt2D}1X_T$fC|lnYZ;vFSEOtg26Zc2l#MQrB=03tPijQZT#22G@NRVcXLxL0~62|yX z-2Y~b%dp}#jQ*c&@qjVX7SA5T3w%4<;<&fOkuf~9M`yzuH=V5T-Km&dC5HI=$x7Hg znKaRiarRAPr6uk`w->~avCsLQ8T8neGqhc|hsmNW4dh z9!UIzL~a2RS*V;vm4~n&VYX8$f%AX`Ng0DgG!kigiS((!II@7s4M2-WpdyGUtQWfj z6_evT;dn4l&g%qQ?qkVionXHeJh{3vT*p%;0NN(lH zX`KpL9%sn|I>CNxG!}Y!zj+#qn{^g>lrsZ0-2JK7xea6G*cizE=s3MU_5Kd6(|U*W z0(yr!V0VXZ*SX0K&DU9sV9yZ?>X44p`=i5pe{|U0A4f+8y+dnt7TGi^OTnTBU1AfM zZ?vNHq*2jv=tWN&6&*$=deW%qFgnqbMx_IGcVb5e2hTW%qO1gqg~VbKYa|xb3mu1E z^rTVIVf3OWjfxJV7m`H>>>iZ^I*a^up!~iSTABlGdmm`otxe#$n|L~AvhVeN=}5g_ zI;{6ghxLAS!0vus)S1e`IiL^D9GshR4~~x02j@V?_`9`DFQ98%2kh=w``=guV6wwh zC~N`Ssk6{=Itv}v$6tp##=isMW)X-rUj8z6q6eQs*sp>%*_YcDrPp5INXY@Se7B|_ z*L&(<>97}4({-G#={l?{x(+*ZP1g~AZejM&n<0gHR%fx2ts@qsBRWp+sSfKs)nQ$h z9k9EjeThRgbv0wYyH`(vHhQLdVLO#!f^@$FpMx5b&qw#;fz!KRfSSE8qvmfYr1bfO zT;xN{wZCdA-@ua1$iSikyGkZHWM~h=fTk!J(YT2K@`^@(|%OjnC{VeL*WW zP2>wIbm2Eoteb|Xr2p@t2w@_to`)xN3MG66lAS{dzXCR0A*2>h=td5pQ96JsIe^A= zDxn68$Le`lJUM%&oRMgn#|D%O@mTW=(&p`OJ3Q9@lUi&p5ntAK#2fYjNG_aoq^>HB?3lehQ5eCh3(7wF#J zjqUl`1#WLIc*$ls37WSTykrN`nzt9cF(7plr7L*1TIRoA`fcYySG}a%=tz-LN$e zT`afe{T92o=Ak7dU~Ow2YNxb&YaUt}jIDXJHFWUrxWgNS7eQO|&^tMKgLQXGZ*b?G z?wxt)R9TmH=AYducjoy^q&GNY3DX826iv)#>PaM)83|^}FgNe)J&V1-Hxih~$)o2x~m&u)Z$a1#_ z7}Ci6-8=I!%QX-1qvd=HyG=}A!Q(9tVs0muV5YONG-uutkFMb56}CVHXFH$tM$H(t6Xhy*&XAz3~OQXQoe1Nns83n%fD^U%OE6Q;R`OldBS6jGz!aB8O9+9`S=>$DDXin3LCJ{JaKi6 z+yUCw^2f*)oLuX+1(q@%3wl1GkBXk_P`s~LwvP6CV%s`7@29Po^Zw#`ZQg(MfME!9 zJ8F%gE5|%<-5}?A^BRMU>#f`5p66YwAIGc=@};<5*I|?n@tq(pZ<6yoL+JB7p(70U zvT)Dy&?S+WYeBwGKn|fx5|PgLr7&FRk`hdg@xC_;>t=19uiY%?`Kirvp1=CAd!9#p z$cW$E&`jZcm=|D*XKvx{ZC!%4tuyZsd$#D?x&*ncOOV^T1i7tCklVV1H^q-zzFW0zUBNavtACzi=p!E6CbxChwz;=;k)>O(es!@%4qkv+=KG7-Jrxns6okyAu0JNHao_FQ zG_HD__mJDV2oIJ658pBse%c|Z{ReUR{=^Jgt#N%ZP3T30jJNrd6B|4@~gB_8jui$UYyen6ca_gRR(SIc}XZO<~*l zaOC9fPDdmTxtM!|%liN@-v3bYUPmGqiJm_q_c2(IeE4Yd@VA;gH8?AmQQ%$Vy$z=9 zMZOcHds|UX$EjYt59Reu1G4v=8#xXo@OIYwt{Vs?U>?tV5O5jz$zQ+gARf@wy=B|S zuYh>&P?XSdYCFqa+zAex%yNmMo*z)BQ5^54*#8T(bQk0s8l#Bdr+BP`IJ^PmI%@vI zd;!GPn>gq=aOh1ObQm0Dn{`;{aGRS$F3IC(5X1yj*a4nPve043qCihedE|B{f#@j6 zL$+Rrb$Q$^K7Wdr_t^p#QePURz8oMB`qCiB_cK76eoWW&V`RpH*$SH>Gh0Q?(|lZU z2=u664cZ1VDj9VOtKej8hXI|t8qI!EZ}xDWw*xQ*qVfb1i;(EK3%R>Q+ta+4V+-I^ z)Q^z$4*=3sHA1TDXMnSBL20O|at*6hj?}bRscHR4(Nq0<>{i-VO^Awr2g_Jbt@mm zO8%6PYK={Q}tbXeCd9o9!a(?^-0QKX@tqEpP}&l5!&ejP`{ucx))rzYzdy~#SP zH`y+lcJe-cW6^Sw`LB$|Y@=x3$+MG=0GT@xZ0RQ@`Xwt~0C-8>4E+5D*(H?KB*s0% zi#YEh9(#sIjEjM#uy4S;XNTEDC_Z1Wn!gA-~yD(HKC1qh8nBp1p<~C zV>)F-t!8;QQ-IXzM@6ZscgdCIHUgolcgqKzYXNEcayKK>_Pn@l7mtj44`^w_ z9!i7_8;xe2?4jGRwX)(*Vh;*Bq^$~aYtRNJwI|8ftv!8_==mdZb?x~NTZO!ZG})hE z!$DuORc;*FD$46*tK2yqrYcBr$m;s&RDqxTX|_rq{eQ40L0q#{Zk(=90d82=Cmq)H zX|kJQ|1ZFMSsF|aDBZBS3&i`+@~)cQLV*J6%Ka=BGSlpq8`ojC+;E58a>F{eg>G(| z-9o0E4$m^pZn@HTP#Xtjp#Barbk)JnC_zfWK97e+(a6!X#U{0-A7HXwnQ|VC1C;#)_>!$jN!D#m zPaND<6lrTHQ_hT@?879tt(l2h($*|PqUSD@(6vRgHQ0n}w&sN(-PZJiM1=GC&bHP3+amH`O?0Kbq=|16V?7A4(V4k+y;+m zj|2M5hE|Yww1<3CRz0{CTXnW46%xIQI)f9)H`+_CPz3TTr8V2@HfDp!m_?xpG(2pd zv}JuzO4>3VuiG-2LAH!C=nRFT8#BtG-;ieb(d-steE@r{@wl^Xw?I+LW>I5rp_uj% zlr5v?-a@|IEd)WwWu0#TRL#NDy<3R_yJ_egJlm7$cH~Htw;06wp95{j5i}$j5II;2 z@OK!TEv5gj$fBJ7GG`b?iTb>%CK>jnR*iS}%fYq{g6zuVDDx zUkRwBWLn9-vg8PI*VTS1t!YZNgGyRem7D^tlvS2eM!rEgX0DFB9a|suI#a8CpkGm| zm}<>Hq*@jRL@iaS^Np?`fNqb7!1Mw{yK`k!5y;RL)jH}p#7S4w z)ltWRp)2az=<&GGrQC%$qd|EXO>~DBX5d+teCCXaOTP$V-lxYIyKZ8t_QY8R7qlnN zolh)jPnJTsQTg8$VsV>+?)OOuQsR=lhS3vN6vPXA1QT)Y~Gl{!5sP87TL|JNtQ6gbcx z5{t?MGH~F2M!fZ)7C89eOLxE!kB9erKvgJU$X@*nNeUQNd?f=3cfP6x3`f7#@pzbQ zp%yR<97bsh7{2S)WxVb#qOgr-Z1oEJaNC_*uOtUE)p}} z;3NO1Q$F`Y-^1}>xdF4_Zx5E`DWB>$|EDL*J&wy5#MtBf@27lXI-l~1(N6i?hq)hN zi0S;WIcB=}=(vm}{&-vlA^hHwvBbQ$WDw#}g2Kg{Z^U(_f=>9;`Fa0L0Z}i)ZiOh>xdVMFDdGQRw+vWk8{&=Sx%k3=vrA{y& z{iPiNJY3Yg&olg{xmhMimaD|0?}O!I|ITtVu}r?fl3-#<_rJ3wOlOt^>n!()q7T6G zZ8uAA)}1NJzr@lH_zYhIMkEhicOFC!%fyur_}ZHqfXgIf`v!us`IFq8SPF{#R6DF% z`sPk3*3Qy*b%HIEZ}gk0;8~OG_dVjP5Bcqw17kko^DVoq zvvC|jGXc<|y%<1WTDSO^Mp&0e#Fr;|mF+dX!Z3=VA{-$r45JENP*$rjoGPRP>{%pc zoyNhJJ5TW>OI1gHCFS2KUOvSOBOe8pgj_~Ke!rtg85Q|O1bxg4xoSI2@w=Y&0 zD%zilP8Uyp%nKs!lQ?uBpE_`mAao#~+H-ExX+9+4s$L+A8k~f6l?r50fpRhZG_UlZ z0bJ>22%W7^=~R)}|MqDz7YD@qXZViTZ1~Rx+spf4q2obDlqnv(!t!;X)pA4XUPr*4D6~jy25otz5%qeEXkk*qUXkb|$sk zlGctjtlJW!kG_U=TM~oy1Z$Z1^@<@koQFykpH0zx<#_#Q!%d)RC1coj%11B_DD5w&4Lwjo5yH3mk7+_ohKR-V|QC z0J;}$4IexLPMP_aP4}o22KQ|@(DSU?dsI4U`bfJ$J82qz}NmAVbVsBH|*>Fw=q)?mkwE1?THkI8$yH<1fkuC;DEMqTahM$_3{Ig2F|w zOLDz6(c;`6-mfm+ z|H7}llEFK;_8Z^No)i0=`~k;jn2zaFF{6KC{o#(b0?eQd9=|A~0^#t+ZFj=>@=MGc z){u?JEWuvn_fT!ai`Sc`A~UPL6OIM*tVcV+I0KNiyAzBf09glh7;ZM%t0e z_?-ub&qzYg!6cWCRR!f@$2Sj#i)t5&S-n6bYuzUNZ4Eg#g8B&A?qzLyRQws5Z2oa0C!e3)&AX+Iz9j6OXgCQkd zih2QEiXE_9h~I(w4I#dvkJDGIC%PbosN-}Y>aZ?E9oB^i*de1Ex)fbHi=0P6o}@Sw zw599}kR1++#C)33~k$C673+MGldehriXdtyYqgQIJ2# zY@rGc;&YE4ad>uNvqZc^`*~sWU5k#Q8N`UBp83*0$$jrIf&C-klH;Avl zMd>r&%~Hu5kJQ!<=Ge3S16~?Y45H)6-inFX_VuGFFjsm=cpY9lFSl(nax|@&E45+@ zcq+*cVl27%>@xQm|0NZWEgmOZ{3tc*ZPfn<7(RkbP2rTBQ^36h++Gc*&V3&RzXFn^ z`<`Auuz<4(l}H~4rjn2Z#PvGi~ht@l~W!0c{2YGI^~%eU==X$H zIfQy>{DTdR8%)DW1oDV;y~z3tt&4`YrnTNzw(ccV&5+Z~PYU!TU^&7WD42N@T1G#L zwDCYzXN5xF-w6ljOd1-!44gA*1$0=qGv9+M{W2X{?%EV<;@#O&D-QNh&b#Qgl3Ce_ zHVzD&M{d?_op5k}2T*BhPr(voNE@VM-~#`hyW0j`adTI4lq!^^0ls2&tEU{`Eac!v zD$)hrmUY*tr2}UZahhmBrkGJq3mLOhk;Tev+Se())k>x?&Qe>`o zP*_S#N9hvNVO?T6tV^s5RGNNSB$A1sX9mDIlj6`}5{I5HSV9piDGwc`%R`5CYZB|G z?d}jYTXx8-m=cgK+(lO4t1r4K=Fwovw$ahf5;>>7q6H}rSMj?L;+P zMHlMFGTK+Mgm^_6+<*oz8-zYpz6HC@m-R)V!L_rexv@iJvzHU0DhCkTr$qTkSK(c?PrHUUw|;b8PBwRRpcD(hgB(cR5x9x>XYGnz+xjd$FPWR;5@jOG&~ zZ&=WNLqMig+;<%huG}n65{pI>)%Xq;OLZ2F#3B_HwFWm5ov}oxj>=+}qFXld7bud7 zHYbyCW)Q)~4uW6l1ZNOIdTFrKfnC*%gXr0=4)QaIJQ@0a^HDRP6L}cUVIV&YTmD}fq>&qr{UaYoLxjDeyFH)k)W#9D>5>|BVI1kgW`dv#ezML%B5p^;Uq#Gy z9$Pl_Y4n3OxBhXAjp66c;VgbupHf#D2MOhjyi4a3G7RJ9pElBC=qDOb^SW3ZD{K$~s^$>|oT zn5g&&ikve<&Qp<*M3HjT^bXh&Z$)Ecx4uwS_RY<)HM1n%y zOb>N4gt|w@Bg^s#5?{gXx7^Fr5fsd}Ai_;+s%#s1K{CQEgV`1YvqzRHNUr!9 zaItOVLr0(-JCPeMoN3beB^OM#;+u!N223mjdc z)A*QIaHlJSEC_2>$$WMke2j;_EwHf9;_bcIgkN=g>W8V*Xrjmt@Klgl%`XO4+g6A zw($pns{38D8>bRS1i1q-+DSzHRAM$lullLPDol9ysl-TpHBpss2d4$A^mcG#uu5+S zkL{{zZwKROA~B_-iEFy51=`WXK=Ex?b&~el*^TpwRo&El?X|Q2&H2QqyHPYo$n%M< z-BkJ7*}t7n^bk`*)sYC!bULK?CboEVNbw2Sy8k$&SQ;jyGym&Dijm4k!NiZaqb@(F> zDSnNFc1Y1GW<{y=V(|4SReLcQClz1EoTZbB{i9X+V(`9b_0hO53KVln6>?bWBUlTK z>S;p!6G@h)AU85s}S&~ATEElX)l9Zjn3kb`YEwE*9oUud8P$b z^fG~uv&`5|aKIXkg`SUd5t7BvI*V+|*)EpGsJTHyP|=Ev90VV1O7?2xj1}+1sN)?< ztXm9?QVcZ!d&<+Ax2fc3yaZT^#RL!5HVf^0BFcS8Wxh(i$#($POGoxz1;{PGqbLZo zrQoCEy+B3EPsi!|S*ea%3-boZbr^)_bADx)yZ6?oN!+S!7f9whMDS9HA(Y9N_ewbg}}Xn%)W%|HyF?a`1Jip zA+aw4t_XE*;UN^rnhaDU^0JQte>1f5SzvQ0s0c?&RCQMa9He9skqDoF7F+%e@}-XT zCD^TB{b^)|pp4Y7twkUx)k{a|1Ea(G!050(FdeXaU{-+8L^(43NxjB`1DGo8ksZW= zv`a_nd1~sN>g_TO3FU=Q_rHLCPp`| zLyT^?LyT^?LyS7?7UOe}mi);{IuW_DEhE+5aA2hvH5?|NE=RqPE=L{K<=6qc<@kCB z3sQvy^j>ztu5Ke1WU6(X-U%JnI{`RRR?>T+7r+5FX-Lm>uy|P%CaQrB8vi_SGNEsJ zyLDJ^w+`#=?ttCxzSu#O+Fhczd$?MY=x(=;)7!1Xfe!Z?qa*Zocfjs;xBZR9c%8*~ z^{CE5$LTC|SQm{B>l`!~{)8@?Kxm5mWxotd@PwF=q=to&O8x~FnlihM3&-G(6^|vs zecUd-Oj1KkQCL>yB#AEZYJ_nF8W$xZlGPBtJ%v!=qB>cPV~Jv3vYO9Eh!>L8#8f(h zD1*pM@ZH$$Ed}?U_=?14-WQEH3MhL#n(+eoH;A@mHN){?M~%B>jZaV}a{~lUKdFnW zdDeEomyuCK$bX_T8m@YsfKRQIEFlM?k>7*89R0AJ!1gFMMQ=x=r0NA#lh(44lLt`( zP%f2O4iuDBNhCy7?tSICwk%}HLs0&Th3J)}T0wf$zj3;+gVQL8&H5)3xSB^ys{Nqf#BHgB=FFesIPB^&DAKn^Y^MMjz$<@m0H%NEIH zK2?O0Y-OY*La+7*irK%yW2-MAG3{I$p`@UK6bn&FRcP=Ru$3r zP?J4aAbapFz^b&ZCvckxDsoojuwkq~$=>D0&;L7q;LE`O zF2d8%si)F)#-);R1_)E9%4Da;>TH@&%y!bP-X?1DVAd75Ob_ZLeuTrhUFo9gFwX5t z7gdM#xjhq9>1TW12K!7uX<4VT98fGIxQ(dV-tNqA8rw+xe(r?Bsoq{xnt1oVf(+@s z>KL5r{X2KJeO%$@F6WN}TUx2t^srGIEb6KpEF7F9>7*voU}dlo5E?)X);k%x%rd0R z1SqD_=@pbp!{9UlCK=kK3_k%Rhw3v_lQJ9)N>YY7%rP2BDMTHq3sHx4A?mO$#Eb53 zNGUDWDfVLrh#*Nx$B~ru^bIMwG4iz|DJH#$?&P<-=_^GGLA53@l)zgqq zS40J`P5_Rsh+({X32<~pII4N|pO6S$5rcX4M<_s7gq;r?j{U9X;iY`P+b@M<%% z>58c2)mwq1D`F5I{x)!QRc}Tex+2PWwH|l#`Gi$xq99!n19>$Cre$y%-%qM$C`?yG zF;~`klS#lbqQ}k#V;e}Zv!zBw{$@c>@I|JEnR6A@;L%UT0GW-8@r775?Z$_j43%?G zSnc%TCPUR-64UYFrs{0fI+5PVHKx`h$MgdJ$PYIeZMRdBUdJ`|y`PfwI<6`CQA*M) z`=%6`q*wM$>8}x%LS?25Nr6IR9y#7F1M}3i^qsvkJyrV7UY~rmS85MT#fXcjdfJLd z!l1+YbNYB;l20JWcfMqgD)C3pD*AUPOb>W2c!H;U;DE}&POuLS zsEq0i&*PC(06!^C_fc>1KS1nc>tZFpA4H$NYDAEW*3xvyiVTVDq$OR<=&Kg+xODM+ zU&Qb1>7u=_I>5(D?I?~+0Lg~^<^2$fig-H;W3C;kdnQg(=>kZOes73{{ncnh`!@G? zE3rHaZmwK{Ohc!ySDLHVNleGrE1msSt2_(tnMw+8A_b5ymV4UnBKRGG%_4Jv8a$9x z*DK{2!jS5ErOQk$$}8(>QQdG-NcnQPY0WHB$n9M~XzfxY>5CKh4N&`}lahG%x*aHQ z1AWa%o)`BXNUx3>si3CNrWH*{L!mDZkP4kupwee9*A?grZ5qVh(iHk)fmG<|LX{4U z?pWf5PF$7qGw=Uo1v)+e4TQk#lEbx}>V>z~M*-l~hUPXR)sgTg;G5 z@kyCFxQIfF8k1m|Jqob=Jm6EHL(aV7iz}U`Ux-SBz5)dj2u~+~a7ucXm@-I>_owiI z*3)a8disTUc#t}RZ56*Fmz%RhP`SE==VpoB0>9toG0dy7!L5>sN?{g zIRpdC4oW!bDO&OIvrw5=_#|j!7S0-V;QVpQWLhT}XC|WO0^TWDr5YrTRj89O{5=Lk zh0coy2CK=Y%fuo^92%?^^Wbd3E7f6M$#CIhS53k;SdA4+D-qc5Ctj&klUcR+SEbrF z=1vsBFDe%eTJ9cbwuX0w%%h8ddr%Y)QE%~nO)CbYlqLQ-L>&Ur^;ynuq9wkdgs+O_I;*O!} zMEsYP=Z30%!}sJ!lF9SYIv#-60QJpbk98umT8%3`jskLI>FuQs$-2l`-N`BfJ4u#s zoh3`KF4^zJ)@rqqU&#>#!?EQ?$XDqxNSKGI@l{=N(F^&0TCv<kk?e)a>diJikW0*QH=SyJmOWH#|9)9Pky$$T~APD{w z;C@Gb^m|Ac^N@HQiAdO-VQM+I4r+WQ^n5Vm_;kZ55pnK%_4h*+Kas{ zZXKbx)l&jr z06Bt!hN^&+L?e+Y3?`blGj%+Gl9d`j^H)~B1;}9W!cA(ZV_-emTZ<&D+Bpga%%Lf( z7Lt?ek0;kOS37D+&$pC3Uw=HgE?tJorYE^N@F4nZ+Qi>LS=GS!I|exJ-^Bno5ibP* zN48OR4G8KQb;mS`-%h6{l)`RQ8=pxGB_l~WH_2LBg_~prrR)q9%F$T#lm+qR9tcWf z$+{1e>;urAzy{fVdkgwvcv_}Q_2=oO>p7KlG=3eCGcpGTuxWAQp!-er&@f20h6D4D%3$uKzbYaeq z)m<38_vZG=dykVY%&c+Jg=rn9xiHI}r}Zv*0e)Zyq0>MTW_gf+nRSdKr5`M@ToA%!oX znHLh-9ypL#TBDXY`XDdq1uIaK$g>s%4(<-H=6Ccly%$!j##($SqsAAcUj~>AV^n)L zOh*6SFk4?j9atUJtOgiKhNT^|lj3oBi+vV0*taAjGp!tqQAe4N%;?ipX&Y6V>p-n^ zYMEYu{Uf0lz>J}&Z~_UKreNF*0BzLpTb=<0DGnXw7KaX!IBb=ul8P#2RAtqBsFE-S zs2CjmGk;E0(@9{xW0kI)NH!ny~IkpkNy9;;Q;7#APZ;_$&4kyHocA0ry;)a=N! z5RQ8;)FVlAVK=zY?^K~UQm1y$>iE(;uN(!m`%A&{OY^*{L1Lt@&ap*>LesaQx=qG^ zTXI5pPEkikXx|MUjB=J^pe{XklWihk)x7`CDe7hwUytfquLhZ<_wJkW5|twF-8cPX zN|N{Pn<49x_wJWNpCAd4-n(Uuj}JDB}y}BXSXm}pwrT6YP zFcF9Vxf8XlsHCcS;^Uc8>-}fRgBiEZ(zV_)h)n?9usreBEUER^W~uaPsQr&Ls(Wac zSv6Z8uXuE}I)FVdzM8ErW*>@ibMW;4H?d|8P6=4V={YL?%NAjttIlM@#Dcjv(lSRh z&sD7v+Y>wFeyoQkce&$&SSm%@JS@`Mxf#*#Xy;dF4gc|7E<@FJ)amroIk44tFz1Y8G?IgTYIe_l*=SP$Bh4z8wE+?9{PU(aA=?W z4*(kHcWm`{p-iX$0KlWuCz#FpCzyLR8R+CozyfJj8W-pSHg|k|`P~Il!0ij9S^4c{ zL%5N4_1?n2lt+v7{RWfxXrcQcjL(e^Fn3v`(wj-u$5r|s*X%{|49sKisPyUOBe!d3 zU@Wg162#iY7@~IZ(PCA8l1Kvv1zk99>5=Oo>c-Ov{Tq+)?C8bf{*5^3wM)Fc(Ri%K zVUS9L7;buEnlkjx9OqoXd?Z?8F9Ei6KFDjuz8kS9yH{jxf*?68hHNtYc$VdiP1tOE zQarQCsKraQDL29TQk->@aYe?W{IE3g_i&`q90&sbz8WLe;-yYU9Q{A}>_}~kD|P-y z&yH-EYjHoOcC(T?F=44Q?i|Z~c7*#e{x3|a?!EF09J{;s7FXJ|es+Y?M!h)l!#s;e z?%WqXHs9)qn=j9^xbt}LZH}Zl`+VyWYanEAf>^fOlNTC4-@?%GtT=hQ!5fgrw;Rq4 z$WBo=AS1W<@4my}!Ml&|PzUcKxA^DX=^ni65_JQzOVka>F6suPe3j#0cN*ba{0Z%x zTl}-{LKD1PTzQu~gSX&r_Y59h=wQR+WytM!%QJZL7XR_P4flnP@Qp}h3%B@d+G7f& zZt?GhVBpq=uJ-hX(j zBk4YQNbmpDE&fGV-Tm@2>1%9Dkm{ZB9RKX|`9toQx>&S5?G z$&SD-dACwN*>UDBc{1!M(!^7V>FN?l2)$oZDuf1{g&MlJK7dr)H~GGrql7H~D}r1PFGZLokD&iI;3)0~(eMk_P$j2n`l!taMxRt%>lMrPLi!bnZF?be zz85d-HHK$0bglQAT+Pd5je_YTuiy32>nvlmD0EsF4at{f2s`FvutTc`g zrpA#WFH2d~{IZf&{;p)mmZNh|FX&l)GSZN&D2f3j%j;uQ1oDqKafIK7Ye?`it z*jFR+iE&asRlORKPuISx&ItRJmXQsw8ScvzeyLK#FI9^8rAiThX&a=(zhCryO$wuP z23t9y%U?6RtzV`XEdKTSe-}n6*i_`hK|jF$qe_v3Z~Ql5wBt=FjNX6KRcopq4$6I6 z1m1E_469dya-GL23b1D~)Xalg)6^?U0Bct6aB=Qi^2G24T06v}Zy9_yDDR-W;63J` z6hc=Wj0hq1TEzqKZy&`U`C3IOcBb%J1>_Q6t5|)=JuHk@ggU37$Z*~Jw#ztl~?LT9@eho zD{yHqU@q~j62(Vxc0Kdz?go$uKr6kGp*2Z{y1oxFPalEsB!aje;zhr})0ZbW`-9LoXaKr| z5O>mU2hfi^{nLPc8Lk1mx`ty?-iPUPw|)z_`VIlk7zCg%fGz;~k=lPeTs`3GKNUbZ zfmr~?6F3jROad1JSPo!d9dd|ce+|z0ylwg=2)KL>kbO_apABHqDsBWc7^Pvtq2Glk zpaJItS6t%)0GT!xTk&TASZtLu#dRMVSwUP~a*C0X=|hBGJ!m+~^L||xIP*1F7UTW$ zhRqOJg!k(#!ojlm9Q;sBT6gKJK5fuj^nb16|MIZ^Yoq*MEBy~0Qm+N|>+~*I?hPFR zhk_d-;37@GRc9bWalT@!&M^t;{0V?6piB5?+l=Dy++SraP;*a%lXVc5m`ncy9@T2gk()0kQ8pK&@j&C$nPWK+KjtA$_#Imjd+wh>dFiG;YG5DILK9*{PM27IyVd0{iQO zwUJu?bU+`&&#+WCqRZJF?f~~xmIARJ#!#jAy%g?tLlBHYHeLe^ekXMib3Qc!>9zRC z<<5tw%#ho5i`z&JZLxUZQ;ccyt*?H`+`N;|e3@gf13moAmk4}jqqtojVIIIpvkTexpmyjVpM~c?O-O*6|2zrUo&UT6 zkn^9k&%^Vdmw}2k&%j^zaL8eRYW`!P05JavelF)fkA5!aKWSe?&3}@R0L*_Dej(>S zcYeY7PpJ2o#s%^PhaKM->(m6uM7Y#nGwxf%dBGuWiibGo1&6q)(h;Y19vyn%TjQ1( z%!elaB)5(Z{$%Xs7x^2G%lXjn$DR35(ywwp^y;t9eCVFv-T6>rT?G~hN_!1q%!jV) zU}EWZ-53)OG+uYN$@dv8-5jX56@zp$S^rf`)lDC^1TWUjO6LJDcfN!Nyq?xEJuDIJ zJZ4h6n`{Kv{CbL<9*JU)DPM5d>@j(L>I09->r*cprgMEN?IoSjb84iUc$IUL7;KvE z;|=btsPnA|Ff~#C6?1tU`#|laX6y5D5Xmofulm?TdOs9(F(wt>Y>YvM zv&G>USK&?i8DvQ30}dU$QsGUL*W{h5TfL^E@FqP-jzkkPq;I{ZbEhi(QsSyjIYUan zywZ;WL(Y)WuNVSY&X9`RK*#%h(MW5D2(~dfL;9GmG!fs{~cD1J|i z(Vv8W`(OBzoRAi$56zY{q%E-~XGpbirgNPttx4~S5s@>bwQ(k|Q-xyMnafPfkp9xa zoNsmTp+lF+@5X2A`0%X_677=AGYcELYu;Qq^-XhdK%*2Zty%h;1(*bc*=I@i6>#@% z6kC(b?*6IpgM!xdIeNdP_|kuRl>0Am&kSF)Lr{}Hg- zK%V8$N9nlJFMqQb+9qmyF5B5dQvLx-JFy@c)m|tzC!2}=`ym!oDENZlE5%r2>EGqx zquWr-K%lWlUT$6pQr|_Od3A~jC@rY07hfiushz9AL66#?O#Ibw;T;MTuPX}hyT)1DQTWn7?_j^9X1V0Uuq@8#s%^a#=C9|>|JBZ2^eaDqM{x2RLezu7YEArySA#o?V1{YAPX{{- zW3eVfemU5l;lA2o_dj7BY)7qwW7Il0E>nIvsL3?Bhqpb`j65Ceu7f>UCin3AW|`4@ zc<*JI;fH*_N7BQu2G8=D(XR&I=`*AD@Q(RSd2RNV95eiM&+Zsxe7k|KPP^X)NKKqs zxhB6J9LhE2<=F?jnxmnTOYepZo-9(jQSOTg-AwncY-G#s?QT-6`@6ehy>s(GtbnPb zZ0#Z|L(J@M%B!)vx=Y#qV|OXr-|ykdcD&AWJ?fRRUB1rKy{F07c_#H#0zP_M4zKf^ zj^j+uwj5sP;ga{iZp*dnB?Y|PmYdPb5%Bk2WKnU)DyvDv0#lZwsct2}QOo4gi#dWkE?@hZ>NSQAo?-&W$t@w8GiR!{hF1g3~D zLYn9oe2Rp25Pizb5eX$D74}?WPZ3v_AzSOk-ZImV!TCs;IkI@nz;Gx1*6pN4ZNZG+ z>$Byg?8KA4C-pX?PWl>uIB#H_c;4WF-WcmRjWgv*U+V#cEl>KI^1Oky4{rMUJkH2zSXAirQ zobF5D?CY4;?d~JH^Ur-`cW&$()tw(lEn`}De_z?1Kkm!!96G&?UmQBl6t zageE?BQv-e`8&e!D`$2KXka-E>rKUSc{Y6dl{5RBIH~l(_Y`=(QasmIfhXrRpmrb% zE%yfyjx#LZeEh|gF=th=WF^@0E{j6Nt?=aC9qpd!$@weXFEbdlsRJ>npCI<0&+3N$FzKMZ2rBKaMIL1<77VlKaAK3vezj88* z_{khXp`KGv;|qb5IZPP^qD5Xq|7%Y-SXlP+w8g%NJT28b&LnRjR0iEmWycx7P{ z#PMpn+ZCQYOVkcF^YX*z4a`5BH!x2;Zy;_NY^vqU7^KF!1%HfMad@!V1uf{u!KSk? zXc`Vlzf}wzVWtE}BEHT%g!bH4G=n4n&l4EOtZ5xhPK1*epaJQB+l<0T!$c`2&LQG2 z=|Eg65mRl5rB(Qo2~>BYRvksdOuf!UArQ@Y*qeGY+}U7}?!S6L4`Mq^A^zqtlqmOZ zGGM--+jfy4 zcvxrBBc)bs*`)xTx5VOB^R+PfmRQ_1d?$==iOsKf#aL{A9uTulzC9+zSnROx0XlDq z#jQv|!@*l(Z`DgN*118xC3aqe5@XQh(F0|Ix5S=rpcvaQ!IV#lL6L{ED<7r9BWa?^ zkBN@@j?j{crhGQq)!#9EsxuM!`Xu?5SmiY5EwM?{JC)Y00}O>W6| zlUwrLskC`Pp%#t&bf3LaY<5_Y-Ld_k$`Dk?Hc`@|tjAb%fGm#ULj1|*- zoRB0^(`rPShqz|8oRDni!(#tNb;o6M%u4SW=$RR}ZSV;_!$=k%%rXC|za^-}14>ta zKU2<4QqGdg%cswBrzOzVF(n(71#KPPv*olzG@osL5cr;F5O$+a>hsI|=r2a{U?2_> zaj}EQ1tP#pQThjFnOHLy)wX36T7IAzdC=c9)5Vj-?UOiOywaaFO>vC4qY}4^e7nsr zME*IzSvB;_i&FYpbGMj&j+ru~D{#fUkh<2S;?C)Cmdcy0>r5tk72IXtw8i@9Q|w#m zEhanh6F?#$-m=nXncKx~1T?zcXg8o)GN3{@`$#{tr5}Al@4hI0-EoZvwN&10onxMg zXzqbq3-FegKE+%weDhEXFNhKI%*>vP3)ODq3wii(AaC4Nnj^9C@uiBfQpOlBt^vP3 zP3)M5p(21WMdm9{5^Le?f7$|UR(5rg)1U=-GfYn~#~=dCvN_;(RS_h}2+o720gF%{ zWI-8ddMC3HJOh^lw~m8W`BYHegR4UA{syl1f$u=jNH4%aK{RxI)7Wk**aHUBeVauNry|7NBrfW+Tpxh=Grb=|35~jXkgg zxNAWiSW&9Y(sltVBe`lM@K3{4-2eb<_=n){QPgGuJR#lCK2ZVXn+vtU8$p-XwTGl4 zTV(ljvKHWFKK%(p6TOrp%q#QV!rW{e zVX|46{XoKw%v@lG4MGC9fE_&&56%ocdmP+B z5Qc0Al1KfKdVMg6PH`Otb~B4BWGrIHvbey`;?i~jC?i#t)-!Oqr8Q&%ytOI{y=d@8 zG2=Y5=cG@-=G4p?GK=g>UW*WkB!hYYwS|1PhfK23YZZCH`yVBUx1F7!`+*KeBRfMYEz}x}Ma2C)au*(9v zW<9xCM!P{9vIKZlM%b5^g}GeuUOO;I#&^iLGKx_a=7@2?YetAhbp!<-8 z{hnPt)lPn=o+yz$a0bBdfx|74A+NeP*R2JvLVWuD9!NiLB1*=qZ>pi+!yD$CU4owg zI}jmgf%nL^#q*@grf*tCt{31WaDfwpWhCNTrZ)0*=O%!F`zg398OqFJ%-3TP=6Fw5 zFO=}rz#Rp#jL51R;PTV~*a~1MfSP(F%E>i*-37>$Ryhh&RH#1j_G35`J;xc&B;aPk zLs`GrApFmSb14Iw2jE%)7XjD}pz?A6Tj0BvzVq~Z==%ZS4uLrE4gfzBxCuaVJ%Dup z#sMfJf7N4f&4sJ#SpXXVpt~`^1xRKS1MH;_3^KHXpvlmFAi&TP8{E)p0F;qghBgN- z8QMAk{0+DddEZ>3d6&bX*La%q;cpLcuY+NzB2+yG%*XWm1_0j#R4Z;m$*vcug%78+ zq>Q4zoG}SV;4Fz(5)5TIBpKMfV$edfQ}Ab0_6RhZYaJ#j*hWB!l(zxMLHPhq1+X(5 zgf^xTxV;hgpl9Gdg2enij6))DpJ>qQF5$aYgkm&Tmk?Wk)n>Ss^%8B+7cM2YKy?C! zRjLg-<`ODe5z4edCUVc%C$%E<)&?cGgmYUF`e=jFT>@1$R0Ne|*ZXRNy1SHHT6yWG z4H^K#_#&tPX+=O5hr5K=S`m=NdYAA;D*|$et8y|Z3u#8ygU-0ZES}|3G98LbKo%Fd zgubl^$l`LBP}_=tEUtD5XSO2r)ymn7m=VOxny%2rNf%&m`95*h1vn0UMBI3R83^VE zH17sB!cAm#<`OsQ?Ej@`Z*sbDlg=@DA)JmlxLK$4-9YzQrSRDzue#p>cm2V(m;fLg zXCiZ#&WX&^APhLYOw%q!R8sEl)9(-93+N)?f(q&B>}gmT#RT0m4I87}&^^;|YqWc& zXW&k_drV}1!f(JyaN!A7N4L;^JrT)hI426{@p&48QEsT{X;?cc3IQEGG71$4lq<+6 zDpeGNNO?CGOJ1i`A>r8t7vSseL!h|jOo1jcFT{Wa#aHfE{Jq7hY|ocvTaO@R*`6=U zwgpb7Z0F0e{X5;VY!}F~{SoeZzFS0{HqKo15;=kHJjpHF^@vKA?PYovc$~6TNL9AV zt;$xpRoRB!ZrP4T=<+Aa_GUzZ1%jqup)X?;EL(+BWvkq>Y+2X}p~^PwcFT6UieeBc z%TcyBBJ8l3;22u-CMc~iTKOKJSf=43pLiA`!=1!VT_Dmikgh~R`5+u*veTxA%5q$lEW@8rw{xA?p~82qCW>Piojt2%K!{j zY}LO5!{505>=P+`HKO!ld?bBcoO`i379Tnuz1Zy5D+9z^U>v<1bVLgN&oG%gc*P*W%P#6{m?La>Jsc}?iLp; z!N&S~;KT* zj^&&VwG&4!F`Lr&3=MC_T!mn`hn9?t@|P>-HOtMI|Nl+*|GVCFe_@Tuv)pH|HJ!8E zNl{O`CxxGOPg^IqV#PF{#a+06W_;sm%fOQEtbKxYjuU z@X)n#C+4SX#-~^MQh23Jnf!zo!p6OyiR=|3ad^9UwWe6n1st=^4NBIw*C?v zUF89QuK)hA_x2m)whWZ1%59n1LVo+dN|?^JOlH)!Os2anV{lt0bHrsB3)}fJ$IQf` z18mETzg~VPnti?e_`madxhwO-_3p?2%6{h(NYf7kP{H+lNY; z^;hKM-ihE^g8=nShcKhaUq{_ugC|(J5PZVGWu2NZ2?@4%8^&4 z9-wt__rrC@*GTQA?Sxb68~+S}4)`PvTQ&d&%9I?E0qBzpip0FlX40&e!CTx3vT6X5 zB1g9mJvU*}Qc@L#gHon4MejWZgpzepRH&{h*&5}>w4wAqxQ`%c`3v+DpKmr(gFO+2 z2GOS5MgkI4!6+0CQB;y9gRfxlih|%P7`$?;;D1oT7pH@ICBl{xwyiM(VV9g6g@cl+ zk{e4g`&LZQQYBNY+|W`bQ{0xj@c30NM`%3wwGcrS$w{*oxE{ElAiRs@#z+w!YrO!h zC5+q$k{1sBEsu;?x!s6eIz}25v0_jWXNk-$W{=?OebflW$erfUBAY`QQq~v899x`M z-{ErVf3vLr`Ed7>DnxFP54Ep{yPOGo69FDT{p+`SuE*4(f~BHxNL&RdlQ8tr1JjW2CY$giFW}@IoGf^1TOq5&I<8C*2Jg&la7^f=oVGj>i z$_NyW5hyqkfx@T=lv_n`Kt)jX84~|dS54y)K&M(!nOGXsYXN!^Pu_}iF?WLrJm{0J zge&2ESqVoGP`>O%=gVG{aFW~4-Unm#0nuTrIiy25kPg#K$#k+fW2-qvZx;7&g%r6~ zbhypDrNcHdNewI6vI3tG`))I*dOkf#WZiC_?D_2^(R{nvePkn&;vCU=7`sGHdpNFB zJanAqM*R#3C0x)qfme2bHl7hra4J^%5dM~eZ{#BJ)$L~Av~qBy%8c1PRA?W`&?boL zZTJ9_D`srNQJU58Q*sGBm%)Q<*0_Sd0q*9~EAjVU23amzwwYPD81mRQvs=~ypyYec zJLN0kdc9Ks_vsKv+Sk*BwcYG9vg9Xtjz^HP`8=qX+NkZUlMz=Q07byd&ZXRilZ3@l zgsdy|(#uE?E4Jg<$24*GcF5Wi_?KdGmW;WUPKe3bGUj=3Ii);XK0m$+?tZwKH%C(M zgiA`vJCVu(E741a190T^xsu~qa1<=*?Q8|l>!teGeEC56#~?Z__HuB@JYA$u29s>D z3da_!;7E&A7}a8xTeaAq5w`pVE=AZ=u~rPXR?meXl(VBWffU?~WJ9GR59>;CN+fX< zr?eyDR8f>TRc;k${3&jnQk)({II=ah=xHbwDb*BCNj10!N+u=M6oV2R*=~?k2M}5x ztj+@nN{Q2t#3gr{se|xA(uruUE+bKH6^U}IIFwt((N`S26RUV1f*F7e=$jZ%J_=OR zd+X~F-xwsqX#~AxBRC6gM^^Tc^>`KBQdVXoh$a-7-cPS7aAl>!DOsu9NR1qmlsl-B zv&+r0l$CuDqHGwI`ke?-HVlPh!%%RfVJM7h7|N|G=~*{;M;6zsvKt%J+alXC0)=D* z3XVjeFe(D&RuTL|MNn0Oz}fQh5OBElK~~mj0eWIFyH%<6I__n8x6_Z8iB)%-$?d;I zD6(r&I#p+i2ktiW^$cC0->{t2gygTi+LCEycfZd1BFN&qHKhqQX8OniMi zjyPX*uNiyVdaz+Kj;2DbQDbFOS;ioHgH;>DXF2qd19vV)Hh$i}>wcGX~Q}d#9O)J*WJgI2n0BjM!;bRLVwCCk3E31NBA$ zI1}L!uLPhZPyi}|5`bFhiJe$a2cLllqytIh#!u;4sH;v0tdvJKivjdr3ZURsa3z2% zi995YCl8rt0w`1D-X9<)>>D@6!Q*OBC%lZXKT>)8xbzD+7t$*i{wo1^0$+(W_nYa# z#SrOEIygHj{Sjm5jbt?NA?L3EdbbBqupC@W$1d`a^cH!@{272UMee;6bfn{9rXvGv zB}~T#H4xQ!WI}$WUnV4BCQdU1Ztf%2-fwmpH*H#HEUaKoR?nSh{c`eCaMNTRKUuwp zp7pa-17>QwMunH&Yx_7$?*o{F@;7$r|Nb7LJoxY*?jg3mg7`nx+wjIN_nbpa|NnvB zh6^5)$F<&gP@Qv#=xqo*B#&!BZ$qY7{*XBrt@TfoH%wP2^1nwZ@hB$rHb663NFK#> zl{e@Q%afSyjl}VPHTUuaK9n~&Co%CR`cLRO@+4-5-D%j`;YrNZyXAq1QI9$YB61&- zCo!8I!}9WEvGOsw;NJI`T5v~BV%F@HCo$LTbx&d@H7|~LPGZW}Vqe*dVlpy^V)s-@sNF4`p8Zgj{d$e?qOdqt9ceB^XU2^R?&9($0MQ98b|chaC)@*hFGe7oioNy2?lqWzU=P>GLa}N89p> zi7%Ml2YdUur`FEtc`yZM+Geunb}Pkzpr3Rc6M6^{h{q8ibv=qdVbsZ5w<Ja#Oju@ofEfq3>yDwl@t1u$ z#G9V(qkbv<4PsS6I1QVh9i;AeV+K$8v)DvJn`4u z1(5f74!`6|l6L)X11c7qwuq%Yy$*W_pmXpue#P5>saWb|d17k$%TkgYepyM9_)+?o z9{A}a1{|Oy37vbu{LsW{u!(P&*H}FH`OzU$YR5eE4_q0-S)g}KM>}TXpsr}`j&{t% zVT7R_GqmDe9$S7^T=5Z_$jl0yPKqqo1btr#;{|Ah*F^F&=f)26Vxn{csJ)2Jj`(g#ZTP#YydU z_*@Df*0uV1XdLBtMB^4$ypfCz1;yh%8)Me>V6H~I1IodvorYlM19$?#>|`+a>#rl2 zejU-46b|1Z`sGHsjTN4LZ$-QDf&m+DCj`b{;6(&@6alhXT6fRUze9+np8)X;7j`|) z0+}vJ-l_L!1Ha0RFA_cYG_!IWt35p!SJ(}OO}L>pdTbyDC$3{=f_jEJuKYu_pVLCtt3Cqp}EG zUm^r5!_$9cllzE~_OAtg$RZ*W^s69L+l$}_sQMw|whzoH!DJ+5CD`;$2T+BT$zXm2 zQ?!vU4Fv9vzGyU-(GQ2CMm2-+dnBs{@5o9F7N>Z;SL*{jMtM!&I2r*Ayv;>v2*|)y zHQ-9_2k!LKkrW~a?15`BTw|UCz~}h_K>#xm3=7yu@N}b}>w&ukTqSr{S$hzG)`M)b zz-E)Jqerqlr&!)4i#B>QifAr);f zrO4y?AbS|g1Nd9&gX?!-OLGClVj?@X5I`3IC<}b1tD&NXB9u`LcCWlk@vUajAe6_* zMA7)6d4=u?9sbaKM~69btON*>Mr_yVm4*Wste1( zO9wl0a3n@W{yw_ue|1$wPMgdV)LlhgRl&6B54TiO-3uzC(U@?e{p(LLYZxkGJ`0~{ zKVgbwN2#`oQL3#T?~135hl)EslY%Ygb0yd!N@iw!E~iNEZN?O7*XMGI6s2j#ITzYm z$&6pT0Tnb6O*5gCFP+n&uBw?2zI9HAuKH)>n#vH&R@`eUX8`2nsO|T1aPPo0MW?zf%v+Tf2g20i@b!;!($w=9?=6ZekI9RR9~^^tZ!5BX!Y2B!qTf#^ z+*mZ$iA#TSzhERaUyd4eG(03VuLbOAct~nqib)CYx?qMSuP~ncv;2aw`DZz!y7HIE zjEZUDjB3v>az^$0FXs8q<8NWb4kCEm{O_6_9y%`PPg1jk^{Xj0J48>Q7W{VN1nNyl zm<&vy9)OTIaRN2@_y0J7(mPyNVBw15b<-{9hN7A?XC2lKQLf9IEL-VH6VK}w?J(=?M%zLpNLt~tLWFf*D}tucYp1SvUd8nsu z>07Wmi*^rsoQ~^NI_a8XEq2_Mv6k~1qxZzMjW?>}wox7T-UnsJ?HMPvL#>Rn+?!=k zb@?6SB4#8<;w;`QJM@qzQ}k|Uac%SMaF0~k{a8DzL6?h~b`fQC=NS@0aaMwcPtST7fUiNp6=dG>%=9E&*BZUs3lDrdLnz| zu|MgN8Ght9Tl~8v4a)4Fes)RGHQTBl7rl+M9?z9!D=rrkO4$pI|ewss7 zD`}SpKpAT0%5@Ch@IXJ!87_8Z%Z~astsTOXBRlF@IkKa!&5<4TKu)Bi;!|R5p2aI? z&H^US;+3=4@+?Q+6S`(ndej0YBV9~ig@fT`T`j5a>B_FCd`xJ!bhCo`DI&YOwJqbd zN#Tz9irXh{iek#Sdb=XC(hukgqIiAb+t7oAAW`!P~w zlhoZAQ%DY}yE7)>c*eXXri56GF(7fF;VqjehhO+jZnOFhz^)eCM*wo6QPMNqt#<(x zYu4beTxfWQ?FZ;AG}^5A3@{cN8+uwCk6-U8yLCygsBV4S>DH@y$!`64FN-(K#^hW1 zCe|6^q9QA-If=RAHpMqZ7Vl^bD7M&{Cl*@`R1$DUKZ~6?zrQ6fi@q_y?ab|y^s~|5 zWM@v;eKkOK=7xc?Gsl-Zo%z!W%ek}Bscr;1iyD3jbNC%wDSP+IO4Yj~N|f4HS~`k3;N*RhArLKdG_?L%8>GH%e2_kbbEq zV9GFgqx9invcrEq%yKSpqz1`BH38`Gsmo-vW-dE?>WV6Sz)v@G+2KI(E%I+=IxwRc7yZ7~@+>sZ$ zlgjM}E_g8Rh`9pHB z{3*wRro9+8+M3s?dKQ+RbAfCiuo%ER@ziMR_KXLngayMq1j_A(hh4$&=}rGHnPxvf z*6r5+BVCT?jFa8^`EjaSN2b|%<7KzzG&{6-y!E+}$tPnH-6vy?q5wOO#GkffJ|&0_ zzpTOfvn%2$8zxwI){0slsZ(~$1Z#o*jd*;5RSFS4qnD=?8m)UwwAMioU^>3clhQv_ zHOY|#u|=M)BEHe0rrB|gR+lyfn2E==f3YA=boky(6w4YdKDz9m;)sIdQ(aNeu`Yy> z-w_2J>j_g7Og~AAf*Vg#qM%cFpwFJ>ih|C~rKng(6m)K`1nh`{&dpP?>I&a1zhjyu zZ6|QXa^g<>#Ja@n-o=ryOT5Ir`#$sPPN>5cPBZ( zcaj5qCpo}(k^_9F{bItYviC2gg`$XDA*YUzsN3T^A%rqHPxYbqhY>wn9ms1=6P%{T3dCC>f0@keT;bPTk zva3HpYlk>=n(XR>PnTW&%+qC8-+sE&)p2>eYkJDRI9SE#H7OVXFUFtbgycA#>wV0* zaiN@Z?z?8WJs)?;@5YpYbM7x@Idkrrv#m5eVN;dntwaj+P0vHrb-i6&J;zE)*#T^a zOsF>kt{bkM^zDYz-F>vK4~a)f-s6%lbIJW(@>AkVl3#Mk54z+L4!Qdwk#VM#7VHl4 z0vY8oF!XG~XYI$?8m?!>&V<@Hkcmoe`cA;F!oUu>}xXlZdfQx*e>9$C&WX@USu4Fnl_kn%-}^%;fSw@aPr&Fp2?iV;w^=&DS+12faSBXHhN z;3EKg2z&;BA8zu#0>DRZ^1cJWH)8UB0PrP%uD?}^f#yz4|DW22m)jw{r~Et{>R;P|puzMxYr z90+{X73wk&t6PdMR!6+`ZY0(yI2t0tLR47?y`x>7EC#2rFejJcL<;lOXc0iQOmRxZEfmb&riRu$Z6$j`%Wt#> z>0;^C7{i8z<7766x5_ljiv@(@XK*9`SO%k94wNYNx1+NZRbWo~TNjtg-2~MX#zo>n znYFHJHluJ=*PWQD`c??c5TU(zjg>FP?Xi-@m$zBFLoeQJS+;n8tCd((6U{BW#%H>rUAWH5f0K-v7z0nrZegfl~>a$6R4`ueKeN2 zhW3ybdgM0iZat_vC@VWBs>dRZ+zeE?ONTR$R5lLwXR>!?lfVo}whT0p?or+mS&v9T zumSaqR3x3fVj&qI2J<6m943iH$~xK%yf7*@L>_S35aTO~ibi($V%Z-^Fe%Oi=&pmIo51sdtb&t_IDrlL-@+bsS zQPH|YDwzkpQ>fup>&y7inD?#6^>(pZ)6%8K9=m8jUR7#~IQYKRQ?&oUnk(kU*=Hvazm$AlZ4YZGlK_6PFz9RrXB3f&p^#zPa zTM)<8#KBx85FkPuC_Y7J!P{6V!t+x;B|q9|8av@f=P<38<&T zoEW9T>sl+;ahZ@+5v;)#DkO|ivTsu{Nr~sNLx+}=V2iBz(j}B5gxmo5cX5x zdErFQEbn(u@a%;<9)^j4#mW^8pIVnSu=Ngr0fAN}OpG>vDSn<7I_h1-p5wpkEp$wS zF*RKB3>O)LsD?q;pfxSj>oev_)EW3*jFnsgBlfQKYtrrM-+PSV!B5)oFhyd&c^l z^jS~Kp@!Qo<6&UB)+lQVf0+5j5>-ptSrINfrU&8(~n3jP?NuHqc_M46L*+TwjcNrsSxn z<)kZ|>vceFk<`iJmT#?MvGjXuv{*C5?h*pj-S*y|BJ**3=<%PezPfjDvW#}|L&vdO zIczFir^7@y+;@_YP=||FcL`3QRR+_#Egb>xXQ4U2TBA+xR=~*6R`HH*`$BK)cD3&P zE>q&Z3*{L0X44*=hA-@C6w`ijPiMPR=+hW`nXY#fXScCm#siH5+u|A7XT)V~?FYrM zSi7@0H`b05FDKewv9~k)TpVjx#o~IE_beEsS=<+EmssU+U^6_{E>3yZC&ka*Js|;A zBRB}$yCO5rzR7zfKs5U+#lARuguYV5wzG$OCrM=Oq|lUhc2B)cA2>bQc?o^Qs(3rU zJDm_{twJmUj(Fr&MG_|t$J^QZPGPjSABfrOmqhVwd;2ow2+c^aSJ>8`QmntlT}P}m zvF3ft>*O#w$$l%?$MHl9+o&fLv<(a?hBkjri(-k2pRZKr!+5l&INBu=p5LU>7e!Yn zjX3hjFg39@*&gEEku6icL%fr0_we%JIh5BS(JsZl%$w}ElEwBE`xS!H0N(6D>S$dgL43t=enoJWOH^ICn4Vz=#!Zv13A9duF|-BEEd=P1 zt*t&>lZ`G5TPryh!C*|Kg^gk6LvINk$goe=^=eU=WsiY%ah5&fl%Mf32l_HCFLYrW z+WEm20v%y=t)7<8!8f-M=qeox^cDiuFj0blf&2y|V@n3jCr0?}jlsRpYyA!kvQ29h zbiB6iD`a>>GStx`LzJkBQ0pVqDXP?73j38*C!Q&^sMNlVwpa@;)Y316be#uxlZ$gv ze+)z>;4CKr^zbKXiOPz@I4QyyuFOcX>VizQS*1UM3U|BsFjsJ@V#@~332b5|z)>)$D>K}R6g^tz;oSi*nbFu)FjTZZ7zXu8 zYo!Dy(7MXO(xN_lruUQEv?-SmKJNdb*rFCeyB-;w#o%szuXpr(_ql7 zY0ZsLRJzs!wb4N@h6jQ-!{9~L2HK1pVUeVKe1k@MOg7?LTED@xPJ;$NCJeGl%cir{ zlpzk7&JF{u!ap!{>57fW?hc2FwhNp-$%!`rS_t)ov9&l%O|)?0Qh`hFDw>AaeZgI^pkip$6)iG|_&mGIh9l74iZRa=-Sg}f!G6G3Nw!*AlO!0P zz)%IV=1^%twIL&WT>U}lmpVD*C?4o#@!NCN9#!#85My8j>FqRfc~6BB)Qc{6+x z7hy&Bv>jmD**(Yz=6|BKQ1|9TFi}A{9MKHau^Gic=OZxD!QP2zsKy|Qtsc&)5>>BK zsZedi)}D69;8~zvFFC@!zN`$x6AT&`E$p7iI*ZK4(t*i!7-*IJfx!eO&S9XH`Ui$D zN^uGkMh|Lrv^{^|*bS8-2Vu}6X?2H63#SVZDuMxlR!x|oGDx33$xug2`K)UpMD{2F z_uPPRG!s-b9&KSFS^G)W3AE^oXca{txXZ;?z3eVQ=yUN7h3N#cZDVd&w=5}X*reQ7%srM&}#lZ+nCH1M!Tc)zf0=$Qbu?hr!L5M(uj{7og9<)BS+og>gI)>f$idqTkk`(Q7^o+6^tm5J}HS zV4si-lNs0%7>IansW+j8@JGrWmk?~BgCVFb1*C61P}^Z3o?54tqNHh!&g4D_V{<&p zS);22OCpn;0;7m31nT;uM>o4~0z|H$<0&l9$ZtRRUDscValjt%h`Rd@p@fhkbnl_ct&|H?8kC6xl<9$Doj<2D1(g_6>bI}f$I306ja`@cd$mca}w!uI=txG zq=?UOSuji|nG+eNlbUe2RKItTjCDdLsFPZ!brvXij6pWx1&R}c6j|#eYaOk62~MUp z0mjfS(8EQ|Ae;yqBN2qRW2m)n7YxdWQ9GFqcZW+sStF_8roFNly~gn|nLciYf$-Q8 z_8eXttb#|X^+VHb0(F6849`yP1ckwPw0$(q7D5q(7H&VVcEhkp|eXCHf<-D^$||D5D@>Lvo?@*j*PN_mXnnE!KkE! z^S=`GHIns|NZFmD5*nfYNy!Ga2zeSk-zmeHMr#j@p)Ju{2spKgvj)yD;;SwaWjObw zu7aVor0pcGHo_S$#o(W_)|2%i7z`Y=oTOk`A4y8M6|tLSO4e{&+X~d(FpMACAiT+v zJed}>gCJ9j^%eq|r5H6^wQ%}$0t+wBIgzM?LEY2ZCBccb9(1s@s0PlF5`-R+gmAx% zgiyy2NF^^vS++m?@`0KwJ%zh^A2^-3CP#t{cZkzLT?K=!tYq42VdAv&w36I~T6RvH zos+x~m>n($ZH5(xRcM5Rm>?7Hcx-Y#Iw^9r_FV~Tt2sXv;cbA4o}5$L-AynkAX<+| za00DI9V{&>ZgUEV&>IfnjUtpk<#Uusjf7Um(3HQrmWaPPdZ#y4icXRz0OLeHiM&p@ z;qp8sOr0E|PIk*5THiq400Rj_i&1;D=0vjYbCG4dgU zs_BNppp0lufRUwfN(;eF4uuwVt2yPQ;-J@&lA(^4@>(Z-l09nDKNHUN64gL!qv+Vr zE(~r2=rD#w#v-7o!4BD_wMK&BCLf_rB6TT@p*QEilL>tzEAF$P|?fJ9|1?3{(2sLxWp!fAxMC zlr^ngFiwnwc)1k>mEyf{J^^EE^R@G}^cKR;NR|d#FTi*}pnU+Qjn>rN247iv3!SgS zv?Z!3!6r_I$|jWv0`6uqCR$8UR1=R->qwm@sS|0E*8M`90GZY1`G2sOODmWuF*W^F{s;a=1aq)M2mBBX*W zqLfIGU1~WHmq#I4GSoV?8m3ieVSL?BL{cBrr!a_x7E>Hme58IPsdcnSW&Nraf%qf- z>y>|UM7CzA5a~M^M7Sl;&taHWsiV%OZ(vm3n2k8Z*AXTfN8L#;!yv&g4}yIF#%Xhe zUUew+%wL4Lj(!wxU5nxsuXMCC9%qn6fp5)97{BGkGF zHQd4@)cOcDJjVq!=my;oA&2{x^31joA*-ILZA3yg%fvL$`c8r;shm^i(UlSvZj?~c zB2m$8El90Gufs$mseN^s(ESWZyk%rdB+Fs+hA#Xj^Fo%VXT8&AL;$F3Q4nlhENGGUx%mf73H(zLfD z?oa3#+u;e?&FP626~(k}n`C%WGStyh43XSD0qlPafl73?$Pj92ZG~~702K7z?oenk zs@9P&0cNekKx^F}7_R(p3}e7B9R@=ot&3oydrk)F6C}NX)-)K|bqHJ}{DbXIL9)z( ziRvsYg_j%@t)C?rZV(Y_U4$C0W2(`4S9NGnYnbw^W z{1a+jgc=TRIha>V4}XFRhq0joEH}4iqmCU16=w7H!<-lj@P~XF}>Lyf9@I`3GP`j@l z`!!OfV2tIo#DSXbD4M4R=6V`yQ_N;J**5;Qml1#jF@6k$H z<2nNg&fmgVa-A=bwj!~!quo{<=wi1K)4SX8;*#O^#5O#$Zfe6u=8Bt!+dlEjaJ#d9 zRCE|&kB2p5gq@UlY#@^uo{D}0=P|Krgxw=pScNTj7!3A(U=5I9J*{dOk2YW0!vI@a z+)A9fB)A491`C_E8up4+H9Uor^v}T{q?cg5DZzSL|A29Q6HHaU4;!hG4S5Ex{cNgGO9hOX3 zT^*2CFPIa8{tPAm6$}#n9ju=nkk;=NqTMLlKZWP$)Q0#GH~Dj2J3Pd}je7)|M+@T4 zfhnoS;4c9X&n?kE4=g3%paV~!aZ6y8xMGx@5qt4q<)KL2JIXFd$~aXac*=#GJl--* z{Bsn}g?ua)*4W$hCXq4Peox;fejRPM=x>Uf#@OdV-ATK#I5P5__{Uf~03~AW#@VxR zm4D$lyDIqmV%<$vHNMmLM4)qFzYbgdP6y!8zTXt)!za;n;MA+yo8jgV%P*%mAB>}# zoKGWru$f_g56y?5Z@#|DPjI=Q^5fhX*!)tM z2%BFhQG)V^`zG>7cca)g-p<3T$uEw#Q#$bbrm7Ma@p|zisGa&H;EgNkWiuFjfcA<& zt=&0oP=+F?SKQR|Zd=8vUtV2?ot_*)Fajn&M_F%Dvdz;Q&SKMu+amt$_w2Y`cC32gpI zI1V?fh(EeHH5mY#6Qm8WIfZ0^nBB_CP#Qy(9#W<14J^_>XYgI=z>nc^?NCj)uV%{@ zvsL_9XJ_PGxLPHd%TCrO#}Sz#*l}=sMc;ZmBk-5)iZM~jU{o4xRvLe*eM|!^RsDz+ z^>(p-mw2!q14O>~vfl1?_6vsLwwR*>(8o}()wpN5)vaF!L+>8#+-_k$NQQji)Rm-i zh!nc#xVE|wrEXEFt5=&uumQdO`e7=dcf_^^J77_|920Lh*g3&m2nZfmRmVsXs{Abl z?ot=ePdE1yJ&P5@Ix>U!%%K2Jb5T!X|}*@g^8w9wx+}QV6KPZR@){R z<^L#T>K8EbgBw2*Dgr-I@|)xqn5{7UT*>c~ihc@Y=uQ}J(sILC;rS{59T@e+U*Ve| zW4Y<5_BIt>eG|$q@>BLkUZxPtC$yzpsJe(moo`%>b<1gL2`n2q zPBKRvC%Fg1agt*s4flvRPA-DsIO#0gobWhKI-6gP`}H6Y+^?fy4rq?Ts0dZciQ`a7 zL+yn$T$RyqgglX-Yb36IM#69fq{3MMcoED+FdR9>jt0BCl+Qsb$m_zz8caTn@^U-y zcf#y~p%yrW-|6C>fc--hp6;h$)H+V_)9)iNyJ7agC_L50A>NWdM9h43f#Jx{w5mKR zd$aiXH2YkO+7pI~lTNp@f?R5;U|r{O?O!-1TJ133)`avBcgG`zk|a|lMoqQc{~ z$KPO-`w3iG@@T(c4&%{(iEpRrx-OQyYWEh^f3agiz0a`!Y6dw0F!qAfRr8pJT`2z! z190w_@(D{4fH5Jvm&E-Qckbpg|iDr=lCo0i}H&yv;9W9 znxa6!?>DCTj4r+@S=m5l!WeOdtpdAV*ORK#@{IPrCB1rfGcNS?UL2U}AC+BMJlYcz z73n{8y-Uwrf4Aas-D;=!v$8Y&2s_T_X%C*e#JpeaA)@Iob`KH!#P)~wK5Qp@MA2XD z1Tp?+d#^}XXWJp)Jo{OFEaw--ZbR?v@xmu=E?FK93dQwG}-|w-VNICB?j+wgg z{3V5fTz`&nM&T5H1^$_a@t|G~!i&x2VsMk4lTi-THF_aXUpLnn@#Up(|EAIXTXUgU z-ega&@8d5BsE|36F&?mVW54Dby>@M&$nX~$rI5pqC%ssuQsqSXY`m+-O@#$^Xy(Rr^(9gEM8e;7c;+hsO3ESs2RuEkkL<1E*h|7 zv{<{y?yr}Jo?m27vVxou83T1+*RIAzKK_sMrIltI=lhI!pMSIwTWDNR=pW;sGNjVD zsBpB$<0OjnC*yNy2!W46>66}yTyGVwx9t34>94#(`Qud(<33&QmY(Ow8|sHW;;JQf zX4?Qu@k*=EV}>4EVyEgxc2>4{=Mp=&4GF*EZ7NeFHrvN^Ez~Y(H`<=SXmRFc_8l=b zXx1L>G$+5P>b%gom)oCPM&G<_aq=pAXeSi<)m9V@LiDm%|8?pY%ISKB??RQa>u<0i9QG+b@3^!Cd|bH^>G2$m)F{bxaALcs_?J3yS4wQxx6ULpC!8vnuD0M-p(JB zVO)T+M$rbw1qxL0Jd7I>#tnv^GTMk=&Jb*${A(;IG!hCG*I{z)H*{20&)oFf^daKF zdb@M)u+yKJ-7QNo%O3isspp*)=$Yryo$8awuZa{H*V!38mm|}U1ZzBP9CCMD|1dUK zdYAOv95y+0Z71;^8pS!+*#&kgVht3FTduP=ct%%RQUc_=O=#+7`$^pl z_|eRAw%AwL2bz6^@7rP*>RF+~TkNSuvJY`p)5Bhk;8>q=_Hv_hVV)RwyItWe$oBhl za?y;$?RM6LqMUR{h+aOlu{)dD@$ZK?@EErSYXE-){~lvw&}W*)AtXUJ)-?M{bJ^1O zN#^HtdVHw4P)djkD5sr4*o19nhPh<$FpmS-7KgW}RN*frO@v!}vB^NZt4vJA@ucaer`*6Mz zjItSfYks2&;HxX9RxAok@x(fKu0@QM z9=%iU2(*E4YsSjM*y7PsveZbzHHvYsM^99}fQuDlm)Nrh4V4QP<9YGH9((XiE?SIl zkkI|jg~s3Xa@gg$#%YB{QeiivU1Pu)TaGcPu=kEY#dTAROTqNBtjXsL*6O263Ii2J z$C}xYk;XpVXFS_nm>rheSo9dbn&O(r?BtjoP?+G+-fUf0ZS9nTfHA&sbe4Y_#)E=D zNqVn5%J}S@B9ZVEzV~x5!+^wfl<}6Xm-X$F;c4sOxTZ3W>Uv^kc12*k(Pox$Q8`LB zLk@uOBagZNs_WTPRbg}0WnAXbA=drqo~mf1EO^#~!VVMxUx1YOVdJ0QkH7v)ZwZ$( z2m60`bbpbmr^e8cr|efODC^tx0&Z2U554t*{g_AJEX2#$7~3lzec7(m&kP-Z*?w2o z)5Y7b*wqtC^T$ofE=?<)f=2T70*;mIW7#>rSWsgubecSp&t;nNh_0)+xm+`z#DpYg zh(D_j#+g%PoA?a+H9XoRmTU2bb#@m#vTbMl*_i*iz(5!u>hh-jkRH#Kjd6pVK=dlf z7Kh%lduMT#W9&mCVs%6M8s`^IT~}Ig%1YzvVB_d2QFPEwPT>;BctF=Xk4A!pQLftC zE-~XEcI>zyGTyWF&b@p&xfmJCiaz|iky(gpG2#mcR~hYVi~|>ySHth)vi&^1q#W>L z24@dXFDWaym<&SgL2MJP%g5zKCt!Np1B#liz@s% z6%`Lms;KaE1UU_KuEC6}V)X3%ytEtAl%RS>7uWp1c)Qy+zM%B=!6>{+3>eZ8`R2EgJiiKAFLw4dgt_6*Q zUi4UZ4C12D_z;Nv>|zeA7=`6u|B%uiW5!-SXZF;y)O?WZMq`tq2Lj+N;(#TZ4%y?| zaUE%_X`^>4@QWTOs+ePYfL>* z>@NYeYmV`&<})q}7WOW#Ts%k2c-y`th(1%CUogVREi5pm%*x6!dKOMGCe;94m0#eo zoD$)})wspdbE^teXXF~zxUUt8t6Af3ZS*lJUtHE2&qN`(zBS&6LX^c5b3|eCLTA5Y z&#~mULE{BY_vPhQOF%ayS|XRE2D*K<(XJ3=V}6ae`iMO^ zflE^i!g?}<484hWkJtsePsDv-mm~*r0~i%=mGkNMo6A*9)5PQt?BZacpssRV0UBmo z-)OMCsj=hS8!QC;ikx3>36_rmUFD0bTw|vp%ONM=51M29T5GMz{pHHa0#2N#q{2I~H<@Z2V$`(+}pSJz+_}g|qRvDRW(6%x@G;NA1e? zTs|A$ntF;;QeyW}WchXR*->1hO%!Dx+Qn^}rwVf{>6PWIDQY$d2O%Z$lX%~c=zOXZm4qVn6PitY3oGewG~bB1z`|G0&%H6(dV+{=6O$9ebvfp8;u~*F zMhq9{#xJgeD|BOxE-4rUZ*CJaS??}>XcKd~zA1E4+n9rv{!XYYA?9bpo`3GFQ%{>2 zDoBjkV}!m-iaEm&=cLD!#Ecj>(Kn>HSS-u+3=%DAG41s-ac^48o={7A%!)3dex)(- zy4X?{lc zS0=_}K}-F&6JvVisZWIbsBt|ESHt{nF~)UsA)FuvO^V6WXNlRgip15EVsi9V;=V~S z1L68Vy1EwFsE#YT&v-rNXS{$31}tpwf+-XXVT)S_0tH0S z=7XgMHUR?5~bJV`onDk=Z82NiR<8QnaB%Q5|LD)AFV?pPyrvb-?=Jr}GUa-y3p&fti-U zcr~wtbvuK14Z3@R5-B%5WNw8?_R@!(B;~cHM}V~5BIIQeyWwmk7Sm;fr`=|*i=3`N z9rNW{1+ML)JgP7+;}ZP~%{IJ`@!UewZ`j68MQQ!UcV-1{V8_pH9~Rr|X|+b~mN<)G zEmyLb6v)^`ct_MiDBvAcWvKDHi%hOFU80N395_?nO5Bd^;;%I0GVHD)OSy+lI>x(a z%GPPf6spAi?u*8rUbRV-zCPb_Q z^V;o3i|w|f#diDAV!I7#%RVZli`_=6T5MkFX!jz~O{e3kE-uDBcK0QvcCqO#_o3=_ z_b0`vHa~N&OLjHB?DCsx)5-Zlj^Z^>FD0lQggi?y4U7IT*6W~9Z8CiiM<%2a$1 z>p`{YJBpL0Ra<~xI8n0Yn2ngTV>W(gA0@^oyk4s{KlgI}%a!%DW-unby)~%UOu0~l z&h=Ox)tJ5`ITNu3tQ}52+{Cq*^AC5Qt=%6z>=(IsY@mxFzX z4`i;hu6fW>GuuHq4!d3YGTfkkc!BPJB(e-wnJ$-@yc$m`@-!-*`ll3*0iOoWMr!r1Djxbl&zDMY7mC+`cd85v zyon03fJ%kG2d)BMp!Clxp88i6W`%Q&wl@*ani5bUJ2j!;;!X)ngKsKKzDt(`-&rQF z#tmHgJ9EnCS9X|hkOWqn{=u1A9pZ}$yY*F==JUEH%#$CjF!`wplb@?F`H;fk<=?A~ zueAO}q338jd{$u^!I#lmqu}vgaZBOOQoIJ&#j??3+SHg0M<&`Z`7R2R@2N2P-U^d% zRG9o3g~>lnVENY?Ob zaF0Oqxl;0und7TbZJ!Cpx<;Db!HAkKEl2{4{M$_HP|I1sGa;~pCS5nne*pd*`Q|s) zn^%&287K!X^wqh zzD*8ZEsjrKws+lAc6wk|Bc@kk`DEzZa$)52Z3TTl9l)zvO z@B~%hDV3oTJh9ae0-u#tA7XCHlh}utx9G##>ir39F|eMO@crmEo*jiguGPN`{aL`j zfWUUF?TV*9ePFB4%lk@U@B>`0*eWmsy<&}1rEa6?Kbav@E2bU3BE@26V;I$9@+%RX zw3s~4gjh`elz2Cpi9veIT6{xcW@C&~^S$BwT1=iXPK_Di)R^Z%|{36Gze+*W&XEGaH?A&3BP#$c)HJoKJ}lEA{Zhty-Gg51Ia6 zR_||;@ew*j;#5kKrx(`dw_Ck-`&=?oX>ex<_c);q&wwb*<$()P1r}H^Jb|gtb%N#7_=l8S zC?o{&bBY>sp`bBig&H#;Xz?VpfFF1V1hxgZl(4*8f&2uXhxe6wN+H;yGH_jCGrSG{ zE-=qQT7!vWGx00D@p3|+1u)uY^RorMQkXoKB$k)_%_cdAixMlL1{Wn7kCuwfW@+hT zHQYo|G2&e4+3~OU_(Zmo;ECzjTRvCuXT{k9w{P?ocpp4)qKo5VM`JE_H0EMQV+Q{; z=AuVqo=4G`=Ta07x(7Lxz&+5ZF;_(zb5*1<<8T@?0;e(8Ng8vpl)#vQ4olfqGoqZU zrGz}bTC$jT@@YGst0&DTV|`>X?<3E>Sj_zC(t=`&xw^9Ad$>yoB1=Aj2YW8-Xsp6#5->)!dKP^ zZSx?C#VmWY!sHnU(>!04Z!vks#w=!jzGUBG@bf&3mstT7_==%{208$a6;}#8557xG0B#uFxHy+a+Ap?SC1D<=4`L|v+Xe5 z6U~3w4)e=}nxCZb{1n{n776b_buLL065q%k@pHW0!9;N1a-?Mk;zkkN{E%dd8H(?W zmk8oAO;U%%7r=sM80=GjE_NJ!a+Bi1bes}u6-OYRCH|c#+}sHhV%OdtpaKDj!Vqp?ECRFT;ynn| zQTzwZQg05d50_mB(U@5hBN3IBgSep`(E)IwuGwlVL@r6-5X8H1`{5M2Vk~exj?^7O z5o@LC5N_!Z2^>bVoKu})zR%-XE~^g1vLj(60Y4g?!6#PuGqB~T0#`c37l5~_++P4c z!yh|^XRN{yDP{QCQZRa~s^5QiGadh-1wT0e>WQP;>T5l$jj4 zNfeeROwe%~kYq@J$s;LiKx;YZstTmM3)~lm`%7LtB%3WGl?EU+uaub zapWwO5+)a<0*P?0 ze|XpVGX(!Rz+nFJgiyWE1pMVp^Q_Bek>iY!*x$`S@AtV$7!V)w*B$SBJ$)qOiW!)4 z3X{&)i{!N{Wain*a a%1@Ynb6kFlw70~Jrv(+TKRl4gpZ^1T&~GUK diff --git a/Tools/bootloaders/CubeOrange_bl.hex b/Tools/bootloaders/CubeOrange_bl.hex index ab71a9ae70..0d5a27aa50 100644 --- a/Tools/bootloaders/CubeOrange_bl.hex +++ b/Tools/bootloaders/CubeOrange_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000040020A1020008391000083D1000087B -:10001000911000083D10000865100008A3020008B8 -:10002000A3020008A3020008A3020008A1280008F8 +:1000000000040020A10200082D1000083110000893 +:10001000851000083110000859100008A3020008DC +:10002000A3020008A3020008A3020008A5280008F4 :10003000A3020008A3020008A3020008A30200080C :10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008E53D0008113E0008C5 -:100060003D3E0008693E0008953E0008A3020008D6 +:10005000A3020008A3020008F13D00081D3E0008AD +:10006000493E0008753E0008A13E0008A3020008B2 :10007000A3020008A3020008A3020008A3020008CC :10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008C13E000852 +:10009000A3020008A3020008A3020008CD3E000846 :1000A000A3020008A3020008A3020008A30200089C :1000B000A3020008A3020008A3020008A30200088C :1000C000A3020008A3020008A3020008A30200087C :1000D000A3020008A3020008A3020008A30200086C -:1000E000293F0008A3020008A3020008A302000899 +:1000E000353F0008A3020008A3020008A30200088D :1000F000A3020008A3020008A3020008A30200084C :10010000A3020008A3020008653A0008A302000841 :10011000A3020008A3020008A3020008A30200082B @@ -22,13 +22,13 @@ :10014000A3020008A3020008A3020008A3020008FB :10015000A3020008A3020008A3020008A3020008EB :10016000A3020008A3020008A3020008A3020008DB -:10017000A3020008D9330008A3020008A302000864 -:10018000A3020008A302000821110008A30200082E +:10017000A3020008DD330008A3020008A302000860 +:10018000A3020008A302000815110008A30200083A :10019000A3020008A3020008A3020008A3020008AB :1001A000A3020008A3020008A3020008A30200089B :1001B000A3020008A3020008A3020008A30200088B :1001C000A3020008A3020008A3020008A30200087B -:1001D000A3020008C5330008A3020008A302000818 +:1001D000A3020008C9330008A3020008A302000814 :1001E000A3020008A3020008A3020008A30200085B :1001F000A3020008A3020008A3020008A30200084B :10020000A3020008A3020008A3020008A30200083A @@ -48,279 +48,279 @@ :1002E000C0F2F0004EF68851CEF200010860BFF374 :1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 :100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F003FB03F023FB4FF055301F49B2 +:100310006F8F02F005FB03F023FB4FF055301F49B0 :100320001B4A91423CBF41F8040BFAE71C49194AA9 :1003300091423CBF41F8040BFAE71A491A4A1B4B99 :100340009A423EBF51F8040B42F8040BF8E7002034 :100350001749184A91423CBF41F8040BFAE702F0F2 -:1003600021FB03F071FB144C144DAC4203DA54F83A +:1003600023FB03F071FB144C144DAC4203DA54F838 :10037000041B8847F9E700F03FF8114C114DAC42DF -:1003800003DA54F8041B8847F9E702F009BB0000C0 +:1003800003DA54F8041B8847F9E702F00BBB0000BE :1003900000040020002400200000000800000020CD -:1003A0000004002090430008002400204424002082 +:1003A000000400209843000800240020442400207A :1003B0004824002060350020A0020008A0020008A8 :1003C000A0020008A00200082DE9F04F2DED108AD0 :1003D000C1F80CD0D0F80CD0BDEC108ABDE8F08F7D :1003E000002383F311882846A047002001F0BEFEB9 -:1003F00001F06EFE00DFFEE738B5204C6FF07303AE +:1003F00001F06EFE00DFFEE738B51F4C6FF07303AF :10040000002523701E236570A570E5702571657148 -:10041000A571E57125726572A372E57200F04AFD5F -:1004200020B10E2325726572A372E57202F0FAF90B -:10043000044602F02FFA0546D8B9114B9C421AD057 -:1004400001339C4218BF054641F2883404BF0125A0 -:100450000024002002F0F0F90DB100F0B7F800F030 -:1004600091FD00F07DFC204600F070F900F0AEF840 -:10047000F9E70024EDE70446EBE700BF482400203D -:10048000010007B008B500F0E9FBA0F120035842D5 -:10049000584108BD07B5054B02211B88ADF8043053 -:1004A00001A800F047FC03B05DF804FB30400008F1 -:1004B000064991F8243033B100230822086A81F8F4 -:1004C000243000F071BC0120704700BF6824002078 -:1004D0002DE9F84F234C94F82430054688461746FA -:1004E0008BBB2E46DFF87C90002F38D094F824A0E8 -:1004F000BAF1000F05D12022FF214846266200F004 -:100500002FFDCAF10805BD4228BF3D465FFA85FBB5 -:10051000AD0041462A4604EB8A0000F0F7FC94F84F -:100520002430A7EB0B079B445FFA8BFBBBF1080F52 -:100530002E44A844FFB284F824B0D5D1FFF7B8FF09 -:100540000028D1D108E0266A06EB8306B042C9D064 -:10055000FFF7AEFF0028C4D10020BDE8F88F0120CE -:10056000BDE8F88F6824002010B5202383F311889C -:100570001248C3680BB101F07FFE0023104A0F48F8 -:100580004FF47A7101F03CFE002383F311880D4C87 -:10059000236813B12368013B2360636813B1636868 -:1005A000013B6360084B1B7833B9636823B90220B1 -:1005B00000F0AAFC3223636010BD00BF5424002069 -:1005C0006905000898250020902400202DE9F041BD -:1005D000544B554953F8042F013201D1BDE8F08145 -:1005E0008B42F7D1514C524B22689A4240F298808C -:1005F000504B9B6803F1006303F500339A4280F08F -:100600008F80002000F0C8FB4B4B0220187000F0D8 -:1006100079FC4A4BD3F8E8200022C3F8E820D3F84D -:100620001011C3F81021D3F81011D3F8EC10C3F84F -:10063000EC20D3F81411C3F81421D3F81411D3F813 -:10064000F010C3F8F020D3F81811C3F81821D3F82C -:100650001811D3F8801041F00061C3F88010D3F86E -:10066000801021F00061C3F88010D3F88010D3F817 -:10067000801041F00071C3F88010D3F8801021F091 -:100680000071C3F88010D3F8803072B62C492D4B1E -:100690000B601D682468BFF34F8FBFF36F8F2A4B29 -:1006A000C3F88420BFF34F8F5A6922F480325A6115 -:1006B000BFF34F8FD3F88020C2F3C906C2F34E3286 -:1006C0005201B70743F6E07E02EA0E08384631468B -:1006D000013948EA000CB1F1FF3FC3F874C200F1E0 -:1006E0004040F5D1203A12F1200FEDD1BFF34F8FEA -:1006F000BFF36F8FBFF34F8FBFF36F8F5A6922F431 -:1007000000325A610022C3F85022BFF34F8FBFF36B -:100710006F8F202383F31188AD4685F30888204727 -:10072000BDE8F081FCFF01081C000208040002087B -:10073000FFFF0108482400209024002000440258B4 -:1007400008ED00E00000020800ED00E02DE9F04FA8 -:1007500099B0B34C01902022FF2110A8A66800F0A8 -:10076000FFFBB04A1378A346A3B9AF480121C36089 -:100770001170202383F31188C3680BB101F07CFD55 -:100780000023AA4AA8484FF47A7101F039FD0023EA -:1007900083F31188019B13B1A54B019A1A60A54AF6 -:1007A000A349019F0292002313704B6099461C4697 -:1007B0001D469846012000F0A5FB002F00F0128294 -:1007C0009B4B1B68002B40F00D8219B0BDE8F08FE9 -:1007D0000220FFF757FE002840F0FB81019BB9F192 -:1007E000000F08BF1F46944B1B88ADF82C30022128 -:1007F0000BA800F09FFADDE74FF47A7000F02EFAB4 -:10080000031E0393EADB0220FFF73CFE824600282A -:10081000E4D0039B581E042800F2DD81DFE800F0DD -:10082000030E1114170018A8052340F8343D0421C5 -:1008300000F080FA54464FF0000856E00421784852 -:10084000F6E704217D48F3E704217D48F0E71C2406 -:10085000204600F0A3FA04340B9004210BA800F00A -:1008600069FA2C2CF4D1E5E7002DB7D0002CB5D0D7 -:100870000220FFF707FE0546002800F0AF810120A7 -:100880006C4C00F089FA0220207000F03BFB4FF026 -:1008900000095FFA89FA504600F08EFA074658B10F -:1008A000504600F099FA09F101090028F1D12C46CF -:1008B000A9460027634B97E701230220237000F02D -:1008C0001FFB3E46DBF808309E4206D2304600F061 -:1008D00065FA0130EBD10436F4E7029B00261E7066 -:1008E000534BA9465E602C46374600F041FB15B1DC -:1008F000002C18BF0027FFF7CDFD5BE7002D3FF46C -:100900006DAF002C3FF46AAF029B0220187000F01C -:10091000F9FA322000F0A2F9B0F1000AC0F25E81CB -:100920001AF0030540F05A81DBF8082006EB0A03B1 -:10093000934200F25381BAF5807F00F24F81554512 -:100940000DDA4FF47A7000F089F90490049B002BC3 -:10095000C0F244813C4A049BAB540135EFE7C82008 -:10096000FFF790FD0546002800F038811F2E11D8B2 -:10097000C6F12004544528BF544610AB26F00300AE -:1009800022463149184400F0C1FA2246FF212E4880 -:1009900000F0E6FA4FEAAA0A5FFA8AF22A493046DC -:1009A000FFF796FD0446002800F01A8106EB8A0640 -:1009B00005469AE70220FFF765FD00283FF40EAFD9 -:1009C000FFF776FD00283FF409AF4FF0000A5346C9 -:1009D000DBF8082092451CD2BAF11F0F12D8109AEA -:1009E00001320FD02AF0030218A90A4452F8202C31 -:1009F0000B92184604220BA900F05EFB0AF1040AD0 -:100A00000346E5E75046039300F0C8F9039B0B90BB -:100A1000EFE718A8042140F84C3D00F08BF964E79B -:100A20004824002094250020542400206905000853 -:100A30009825002090240020324000084C240020FB -:100A400050240020344000089424002018A80023DB -:100A500040F8343D642100F039F900287FF4BEAE3F -:100A60000220FFF70FFD00283FF4B8AE0B9800F00E -:100A7000C5F918AB43F8480D04211846CDE718A86E -:100A8000002340F8343D642100F020F900287FF471 -:100A9000A5AE0220FFF7F6FC00283FF49FAE0B98AE -:100AA00000F0AEF918AB43F8440DE5E70220FFF77C -:100AB000E9FC00283FF492AE00F0A8F918AB43F827 -:100AC000400DD9E70220FFF7DDFC00283FF486AE99 -:100AD0000BA9142000F0A0F9824618A8042140F8C0 -:100AE0003CAD00F027F951460BA896E7322000F004 -:100AF000B5F8B0F1000AFFF671AE1AF0030F7FF4FB -:100B00006DAEDBF808200AEB080393423FF666AEB1 -:100B10000220FFF7B7FC00283FF460AE2AF0030A7A -:100B2000C244D0453FF4E1AE404600F037F904211D -:100B30000A900AA800F0FEF808F10408F1E74FF463 -:100B40007A70FFF79FFC00283FF448AEFFF7B0FC37 -:100B500000283FF4AFAE109B01330CD0082210A93F -:100B60000020FFF7B5FC00283FF4A4AE2022FF21AF -:100B700010A800F0F5F9FFF78DFC374801F0FCFAFA -:100B800023E6002D3FF42AAE002C3FF427AE18A830 -:100B9000002340F8343D642100F098F88246002894 -:100BA0007FF41CAE0220FFF76DFC00283FF416AE68 -:100BB0000390FFF76FFC41F2883001F0DDFA0B98EB -:100BC00000F01AFA00F0D4F9039B57461C461D4664 -:100BD000F0E5054689E64FF00008FFE52546FDE50E -:100BE0002C4667E6002000F039F80490049B002BA7 -:100BF000FFF6E3AD012000F083F9049B213B122BAB -:100C00003FF6D8AD01A252F823F000BFD10700088B -:100C1000F907000869080008B5070008B5070008CB -:100C2000B5070008FD080008ED0A0008B50900082E -:100C30004D0A00087F0A0008AD0A0008B507000841 -:100C4000C50A0008B50700083F0B0008EB080008BC -:100C5000B5070008830B0008A08601002DE9F347C3 -:100C600002AE00244FF47A7506F8014D144FDFF8F8 -:100C70005880454397F900305A1C5FFA84F901D037 -:100C8000A34212D158F8240003680122D3F820A00F -:100C900031462B46D047012807D10A4B9DF8070063 -:100CA00083F8009002B0BDE8F0870134022CE1D156 -:100CB0004FF4FA7001F060FA4FF0FF30F2E700BF36 -:100CC00000240020BC250020484000082DE9F04702 -:100CD0004FF47A75144FDFF8588006464D430024D0 -:100CE00097F900305A1C5FFA84F901D0A34210D161 -:100CF00058F8240003680422D3F820A031462B467C -:100D0000D047042805D1094B83F800900020BDE8A6 -:100D1000F0870134022CE3D14FF4FA7001F02CFA81 -:100D20004FF0FF30BDE8F08700240020BC250020F4 -:100D30004840000830B4074B1A78074B53F822405C -:100D40002368DD69054B0A46AC460146204630BCA7 -:100D5000604700BFBC25002048400008A086010075 -:100D6000F8B501F051FC094C094E0A4F20700025DE -:100D700030682378834207D901F042FC3368054488 -:100D80000133BD423360F3D9F8BD00BFBD2500205B -:100D9000A0250020FFFF010001F0F8BC00F1006079 -:100DA00000F500300068704700F10060920000F527 -:100DB000003001F085BC0000054B1A68054B1B781C -:100DC0009B1A834202D9104401F01ABC00207047DC -:100DD000A0250020BD25002038B5074D0446286811 -:100DE000204401F013FC28B928682044BDE83840AD -:100DF00001F01EBC38BD00BFA025002000207047B8 -:100E0000014BC058704700BF00E8F11F014B186844 -:100E1000704700BF0010005CF0B5244B244C1B68E9 -:100E20002788656894F90820C3F30B06BE424FEA91 -:100E3000134328D0A789BE4206D101220C2505FB09 -:100E40000244656894F9082041F20104A3421CD0D1 -:100E500041F20304A3421AD042F20104A34218D083 -:100E600042F20304A34208BF5622441E0C44013D33 -:100E70000B46A34217D215F9016F581C5EB1034609 -:100E800000F8016CF5E70022D8E75A22EDE7592275 -:100E9000EBE75822E9E72C2584421D7001D9981C04 -:100EA0005A70401AF0BD1846FBE700BF0010005C06 -:100EB00004240020104B5B8841F201018B429AB25E -:100EC00011D041F203018B420FD042F201039A424A -:100ED0000DD042F203039A420BD10323074A02EBDF -:100EE0008303D87870470023F8E70123F6E702234D -:100EF000F4E70020704700BF0010005C3840000895 -:100F000070470000704700007047000010B50023D4 -:100F1000934203D0CC5CC4540133F9E710BD000008 -:100F200030B5441E14F9010F0B4660B193F900501F -:100F3000854201F1010106D11AB993F90020801A06 -:100F400030BD013AEEE7002AF7D1104630BD00006F -:100F500002460346981A13F9011B0029FAD170477B -:100F600002440346934202D003F8011BFAE770479C -:100F7000024B1A78024B1A70704700BFBC25002044 -:100F80000024002038B5164C164D204600F026FCF3 -:100F90002946204600F04EFC2D681348D5F89020D5 -:100FA000D2F8043843F00203C2F8043801F0E4F840 -:100FB0000E49284600F04EFDD5F890200C48D2F896 -:100FC00004380C4923F00203C2F80438A0424FF45D -:100FD000E1330B6003D0BDE8384000F05DBB38BDA5 -:100FE000EC2A00202841000840420F00544100082C -:100FF00040260020A425002038B50B4B1A780B4B57 -:1010000053F822400A4B9C4205460CD0094B002164 -:1010100018461822FFF7A4FF056001462046BDE8E8 -:10102000384000F039BB38BDBC25002048400008DE -:10103000EC2A0020A4250020FEE7000000B59BB0AC -:10104000EFF3098168226846FFF760FFEFF305833D -:10105000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE743 -:1010600000ED00E000B59BB0EFF30981682268460F -:10107000FFF74CFFEFF30583044B9A6B9A6A9A6A69 -:101080009A6A9A6A9A6A9B6AFEE700BF00ED00E0DE -:1010900000B59BB0EFF3098168226846FFF736FF81 -:1010A000EFF30583034B5A6B9A6A9A6A9A6A9A6AB3 -:1010B0009B6AFEE700ED00E030B5084D0A4491421E -:1010C0000BD011F8013B09245840013CF7D040F304 -:1010D00000032B4083EA5000F7E730BD2083B8EDD2 -:1010E000002304491A465A50C8180833802B42601E -:1010F000F9D17047C0250020024A136843F0C003AD -:101100001360704700780040044B5A6810439A6897 -:1011100058600AB1181D1047704700BF40260020D4 -:101120002DE9F84F404EF56D2F68EC692C622107D0 -:1011300018D014F0080F0CBF00208020E20748BF31 -:1011400040F02000A30748BF40F04000610748BFBF -:1011500040F48070202383F31188FFF7D5FF00232C -:1011600083F31188E20509D5202383F311884FF416 -:101170000070FFF7C9FF002383F31188DFF8A8A0F0 -:101180004FF020094FF0000B14F0200832D13B063D -:1011900015D5DFF898A04FF0200920060FD589F368 -:1011A0001188504600F0ECF9002830DA0820FFF7EB -:1011B000ABFF27F080032B60002383F311887906AF -:1011C0000DD562060BD5202383F31188F26C336DA5 -:1011D0009A4201D1336C03BB002383F31188E306E9 -:1011E00004D5B26E13690BB150699847BDE8F84F4A -:1011F00001F066BB89F31188AB8C96F864105046F9 -:10120000194000F057FA8BF31188EC69BCE780B203 -:10121000288588F31188EC69BFE7102027F0400784 -:10122000FFF772FF2F60D7E74026002078260020C6 -:1012300013B5104C204600F023FA04F1140000947A -:1012400000234FF400720C4900F0E4F804F1380078 -:1012500000940A4B0A494FF4007200F05DF9094B03 -:10126000E365094B23660C21522002B0BDE8104013 -:1012700000F05EB840260020AC260020F9100008DF -:10128000AC2800200078004000E1F505254B00293E -:1012900008BF1946037C8166012B30B511D1224B62 -:1012A00098420ED1214BD3F8E82042F08042C3F897 -:1012B000E820D3F8102142F08042C3F81021D3F87F -:1012C00010310A68036EC46D03EB5203B3FBF2F3F3 -:1012D0004A68150442BF23F0070503F0070343EAF9 -:1012E0004503E3608B6843F040036360CB6843F0E1 -:1012F0000103A36042F4967343F001032360510598 -:101300004FF0FF33236205D512F0102205D0B2F161 -:10131000805F04D080F8643030BD7F23FAE73F233C -:10132000F8E700BF6C400008402600200044025847 -:1013300000F1604300F01F02400903F56143090119 -:101340008000C9B200F1604083F8001300F56140ED -:1013500001239340C0F8803103607047F8B515460B -:1013600082680669AA420B46816938BF8568761A89 -:10137000B542044607D218462A46FFF7C7FDA369BF -:101380002B44A3610DE011D932461846FFF7BEFD8C -:10139000AF1B3A46E1683044FFF7B8FDE2683A44D3 -:1013A000A261A3685B1BA3602846F8BD18462A46C5 -:1013B000FFF7ACFDE368E4E783682DE9F0410446FC -:1013C00093421546266938BF85684069361AB5428A -:1013D0000F4606D22A46FFF799FD63692B446361E5 -:1013E0000DE012D93246A5EB0608FFF78FFD424605 -:1013F000B919E068FFF78AFDE26842446261A368B8 -:101400005B1BA3602846BDE8F0812A46FFF77EFDFE -:10141000E368E4E710B50A440024C361029B00605E +:10041000A571E57125726572A372E57200F046FD63 +:1004200020B10E2325726572A372E57202F0FCF909 +:10043000044602F031FA0546D0B9104B9C4219D05F +:1004400001339C4241F2883412BF05460024012545 +:10045000002002F0F3F90DB100F0B6F800F08CFDC9 +:1004600000F07CFC204600F06FF900F0ADF8F9E7F1 +:100470000024EDE70446EBE748240020010007B024 +:1004800008B500F0E9FBA0F120035842584108BD2F +:10049000054B07B51B88022101A8ADF8043000F018 +:1004A00047FC03B05DF804FB3C400008064991F8A6 +:1004B000243033B100230822086A81F8243000F088 +:1004C00071BC0120704700BF682400202DE9F84F5F +:1004D000234C05468846174694F824308BBB2E469D +:1004E000DFF87C90002F38D094F824A0BAF1000FE8 +:1004F00005D12022FF214846266200F02BFDCAF1DB +:100500000805414604EB8A00BD4228BF3D465FFA1C +:1005100085FBAD00A7EB0B072A462E4400F0F2FC4A +:1005200094F82430A844FFB29B445FFA8BFBBBF1E4 +:10053000080F84F824B0D5D1FFF7B8FF0028D1D137 +:1005400008E0266A06EB8306B042C9D0FFF7AEFF8B +:100550000028C4D10020BDE8F88F0120BDE8F88F45 +:100560006824002010B5202383F311881248C36843 +:100570000BB101F081FE0023104A4FF47A710E484E +:1005800001F03EFE002383F311880D4C236813B164 +:100590002368013B2360636813B16368013B6360B8 +:1005A000084B1B7833B9636823B9022000F0A8FC1C +:1005B0003223636010BD00BF54240020650500088D +:1005C0009825002090240020554B56492DE9F041F4 +:1005D00053F8042F013201D1BDE8F0818B42F7D1ED +:1005E000514C524B22689A4240F29880504B9B6883 +:1005F00003F1006303F500339A4280F08F800020FE +:1006000000F0C8FB02204B4B187000F077FC4A4BFF +:10061000D3F8E8200022C3F8E820D3F81011C3F87B +:100620001021D3F81011D3F8EC10C3F8EC20D3F854 +:100630001411C3F81421D3F81411D3F8F010C3F82F +:10064000F020D3F81811C3F81821D3F81811D3F8F3 +:10065000801041F00061C3F88010D3F8801021F0C1 +:100660000061C3F88010D3F88010D3F8801041F0F7 +:100670000071C3F88010D3F8801021F00071C3F826 +:100680008010D3F8803072B62C4B2D490B601D685A +:100690002468BFF34F8FBFF36F8F2A4BC3F88420BA +:1006A000BFF34F8F5A6922F480325A61BFF34F8FE4 +:1006B000D3F8802043F6E07EC2F3C906C2F34E327F +:1006C000B707520102EA0E0838463146013948EAB6 +:1006D000000C00F14040B1F1FF3FC3F874C2F5D106 +:1006E000203A12F1200FEDD1BFF34F8FBFF36F8F80 +:1006F000BFF34F8FBFF36F8F5A6922F400325A61F4 +:100700000022C3F85022BFF34F8FBFF36F8F202317 +:1007100083F31188AD4685F308882047BDE8F08152 +:10072000FCFF01081C00020804000208FFFF01088A +:1007300048240020902400200044025800000208B1 +:1007400008ED00E000ED00E02DE9F04F99B0B34C6A +:100750002022FF21019010A8A66800F0FBFBB04A00 +:10076000A3461378A3B90121AE481170C3602023BA +:1007700083F31188C3680BB101F07EFD0023AA4A00 +:100780004FF47A71A74801F03BFD002383F31188F1 +:10079000019B13B1A54B019A1A600023A44AA349F7 +:1007A000019F99461C461D46984613704B60029265 +:1007B000012000F0A3FB002F00F012829B4B1B686E +:1007C000002B40F00D8219B0BDE8F08F0220FFF73A +:1007D00057FE002840F0FB81019BB9F1000F08BFD4 +:1007E0001F46944B1B8802210BA8ADF82C3000F05B +:1007F0009FFADDE74FF47A7000F02EFA031E0393A0 +:10080000EADB0220FFF73CFE82460028E4D0039B8F +:10081000581E042800F2DD81DFE800F0030E1114F9 +:10082000170018A80523042140F8343D00F080FA91 +:1008300054464FF0000856E004217848F6E70421BA +:100840007D48F3E704217D48F0E71C24204604346A +:1008500000F0A2FA04210B900BA800F069FA2C2CEE +:10086000F4D1E5E7002DB7D0002CB5D00220FFF77A +:1008700007FE0546002800F0AF8101206C4C00F017 +:1008800089FA4FF000090220207000F037FB5FFA70 +:1008900089FA504600F08EFA074658B1504609F1E1 +:1008A000010900F097FA0028F1D12C46A94600274B +:1008B000634B97E701233E460220237000F01CFBA8 +:1008C000DBF808309E4206D2304600F065FA01306F +:1008D000EBD10436F4E70026029BA9462C461E7095 +:1008E0003746524B5E6000F03DFB15B1002C18BF3F +:1008F0000027FFF7CDFD5BE7002D3FF46DAF002C27 +:100900003FF46AAF0220029B187000F0F7FA322021 +:1009100000F0A2F9B0F1000AC0F25E811AF00305FE +:1009200040F05A8106EB0A03DBF80820934200F2FC +:100930005381BAF5807F00F24F8155450DDA4FF4AF +:100940007A7000F089F90490049B002BC0F2448176 +:10095000049B3C4AAB540135EFE7C820FFF790FDFC +:100960000546002800F038811F2E11D8C6F120045A +:1009700010AB26F0030033495445184428BF5446B1 +:10098000224600F0BFFA2246FF212E4800F0E2FA8C +:100990004FEAAA0A2B4930465FFA8AF2FFF796FD22 +:1009A0000446002800F01A8106EB8A0605469AE7FD +:1009B0000220FFF765FD00283FF40EAFFFF776FD3C +:1009C00000283FF409AF4FF0000A5346DBF8082037 +:1009D00092451CD2BAF11F0F12D8109A01320FD0D3 +:1009E0002AF0030218A90A4452F8202C0B92184648 +:1009F00004220BA90AF1040A00F058FB0346E5E7BC +:100A00005046039300F0C8F9039B0B90EFE718A83A +:100A1000042140F84C3D00F08BF964E748240020A5 +:100A20009425002054240020650500089825002006 +:100A3000902400203E4000084C2400205024002038 +:100A4000404000089424002018A80023642140F8A6 +:100A5000343D00F039F900287FF4BEAE0220FFF7E4 +:100A60000FFD00283FF4B8AE0B9800F0C5F918ABA5 +:100A700043F8480D04211846CDE718A80023642147 +:100A800040F8343D00F020F900287FF4A5AE0220A4 +:100A9000FFF7F6FC00283FF49FAE0B9800F0AEF98C +:100AA00018AB43F8440DE5E70220FFF7E9FC002806 +:100AB0003FF492AE00F0A8F918AB43F8400DD9E727 +:100AC0000220FFF7DDFC00283FF486AE0BA91420BE +:100AD00000F0A0F9824618A8042140F83CAD00F0CF +:100AE00027F951460BA896E7322000F0B5F8B0F18F +:100AF000000AFFF671AE1AF0030F7FF46DAE0AEB39 +:100B00000803DBF8082093423FF666AE0220FFF7A9 +:100B1000B7FC00283FF460AE2AF0030AC244D04577 +:100B20003FF4E1AE404608F1040800F035F9042135 +:100B30000A900AA800F0FCF8F1E74FF47A70FFF78A +:100B40009FFC00283FF448AEFFF7B0FC00283FF4BC +:100B5000AFAE109B01330CD0082210A90020FFF784 +:100B6000B5FC00283FF4A4AE2022FF2110A800F01D +:100B7000F1F9FFF78DFC374801F0FEFA23E6002D6E +:100B80003FF42AAE002C3FF427AE18A800236421BE +:100B900040F8343D00F098F8824600287FF41CAEFF +:100BA0000220FFF76DFC00283FF416AE0390FFF71C +:100BB0006FFC41F28830574601F0DEFA0B9800F0E6 +:100BC00015FA00F0CFF9039B1C461D46F0E50546DB +:100BD00089E64FF00008FFE52546FDE52C4667E66F +:100BE000002000F039F80490049B002BFFF6E3ADE1 +:100BF000012000F081F9049B213B122B3FF6D8AD78 +:100C000001A252F823F000BFCD070008F507000845 +:100C100065080008B1070008B1070008B10700081F +:100C2000F9080008E90A0008B1090008490A0008A3 +:100C30007B0A0008A90A0008B1070008C10A0008D9 +:100C4000B10700083B0B0008E7080008B1070008DF +:100C50007F0B0008A08601002DE9F3474FF47A7559 +:100C6000002402AE154F4543DFF8588006F8014DC9 +:100C700097F900305FFA84F95A1C01D0A34212D1CF +:100C800058F82400012231460368D3F820A02B46EF +:100C9000D047012807D10A4B9DF8070083F8009040 +:100CA00002B0BDE8F0870134022CE1D14FF4FA70B4 +:100CB00001F062FA4FF0FF30F2E700BF002400209D +:100CC000BC250020544000082DE9F0474FF47A7508 +:100CD00006460024134F4D43DFF8508097F900304B +:100CE0005FFA84F95A1C01D0A34210D158F82400AD +:100CF000042231460368D3F820A02B46D0470428AD +:100D000005D1094B002083F80090BDE8F08701343D +:100D1000022CE3D14FF4FA7001F02EFA4FF0FF30BD +:100D2000BDE8F08700240020BC25002054400008C6 +:100D3000074B30B41A78074B53F822400A46014655 +:100D400023682046DD69044BAC4630BC604700BFD9 +:100D5000BC25002054400008A0860100F8B50A4CCC +:100D600000250A4E01F052FC094F207030682378AC +:100D7000834207D901F046FC336805440133BD4284 +:100D80003360F3D9F8BD00BFBD250020A0250020A9 +:100D9000FFFF010001F0FCBC00F1006000F5003035 +:100DA0000068704700F10060920000F5003001F02B +:100DB00089BC0000054B1A68054B1B789B1A8342BF +:100DC00002D9104401F01EBC00207047A02500206D +:100DD000BD25002038B5074D04462868204401F0A1 +:100DE00017FC28B928682044BDE8384001F022BC2F +:100DF00038BD00BFA025002000207047014BC0581F +:100E0000704700BF00E8F11F014B1868704700BF32 +:100E10000010005C234BF0B5234C1B682788C3F3FC +:100E20000B0665681B0C94F90820BE4228D0A789E0 +:100E3000BE4206D101220C2505FB0244656894F9E7 +:100E4000082041F20104A3421CD041F20304A34252 +:100E50001AD042F20104A34218D042F20304A34282 +:100E600008BF5622441E013D0B460C44A34217D234 +:100E700015F9016F581C5EB1034600F8016CF5E7E7 +:100E80000022D8E75A22EDE75922EBE75822E9E79A +:100E90002C2584421D7001D9981C5A70401AF0BD4F +:100EA0001846FBE70010005C04240020104B41F2C0 +:100EB00001015B888B429AB211D041F203018B424F +:100EC0000FD042F201039A420DD042F203039A423C +:100ED0000BD10323074A02EB8303D8787047002322 +:100EE000F8E70123F6E70223F4E70020704700BF8C +:100EF0000010005C4440000870470000704700008C +:100F000070470000002310B5934203D0CC5CC4545A +:100F10000133F9E710BD000030B5441E14F9010F8C +:100F20000B4658B193F900500131854206D11AB9E8 +:100F300093F90020801A30BD013AEFE7002AF7D17B +:100F4000104630BD02460346981A13F9011B0029CA +:100F5000FAD1704702440346934202D003F8011BC2 +:100F6000FAE77047024B1A78024B1A70704700BFBD +:100F7000BC2500200024002038B5164C164D204614 +:100F800000F02CFC2946204600F054FC2D68134844 +:100F9000D5F89020D2F8043843F00203C2F80438A0 +:100FA00001F0EAF80E49284600F054FDD5F89020EB +:100FB0000C48D2F804380C49A04223F00203C2F8CE +:100FC00004384FF4E1330B6003D0BDE8384000F043 +:100FD00063BB38BDEC2A00203441000840420F00BA +:100FE0006041000840260020A425002038B50B4BA6 +:100FF00005461A780A4B53F822400A4B9C420CD003 +:10100000094B002118221846FFF7A4FF056001468E +:101010002046BDE8384000F03FBB38BDBC2500206D +:1010200054400008EC2A0020A4250020FEE7000020 +:1010300000B59BB0EFF3098168226846FFF762FFB5 +:10104000EFF30583034B9A6B9A6A9A6A9A6A9A6AD3 +:101050009B6AFEE700ED00E000B59BB0EFF309816D +:1010600068226846FFF74EFFEFF30583044B9A6B47 +:101070009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFB3 +:1010800000ED00E000B59BB0EFF3098168226846EF +:10109000FFF738FFEFF30583034B5A6B9A6A9A6A9E +:1010A0009A6A9A6A9B6AFEE700ED00E030B50A444E +:1010B000074D91420BD011F8013B09245840013CE7 +:1010C000F7D040F300032B4083EA5000F7E730BD30 +:1010D0002083B8ED002304491A465A50C818083333 +:1010E0004260802BF9D17047C0250020024A136866 +:1010F00043F0C0031360704700780040044B5A6807 +:1011000010439A6858600AB1181D1047704700BF15 +:10111000402600202DE9F84F414EF56D2F68EC690F +:1011200021072C6219D014F0080F0CBF002080207A +:10113000E20748BF40F02000A3074FF0200348BF5C +:1011400040F04000610748BF40F4807083F311888D +:10115000FFF7D4FF002383F31188E20509D520238C +:1011600083F311884FF40070FFF7C8FF002383F367 +:1011700011884FF02009DFF8A8A04FF0000B14F001 +:10118000200832D13B0615D54FF02009DFF894A096 +:1011900020060FD589F31188504600F0F1F9002898 +:1011A00030DA0820FFF7AAFF27F080032B60002326 +:1011B00083F3118879060DD562060BD5202383F3BE +:1011C0001188F26C336D9A4201D1336C03BB00235A +:1011D00083F31188E30604D5B26E13690BB150692D +:1011E0009847BDE8F84F01F06DBB89F31188AB8CCF +:1011F000504696F86410194000F05CFA8BF31188A1 +:10120000EC69BCE780B2288588F31188EC69BFE7F8 +:1012100027F040071020FFF771FF2F60D7E700BFCE +:10122000402600207826002013B5104C204600F000 +:1012300027FA04F11400009400234FF400720C49C3 +:1012400000F0E8F804F1380000944FF40072094B04 +:10125000094900F061F9094B0C215220E365084B64 +:10126000236602B0BDE8104000F05EB840260020C2 +:10127000AC260020ED100008AC28002000780040CB +:1012800000E1F505254B002908BF1946037C012B19 +:10129000816630B511D1224B98420ED1214BD3F843 +:1012A000E82042F08042C3F8E820D3F8102142F051 +:1012B0008042C3F81021D3F810310A68036EC46D60 +:1012C00003EB5203B3FBF2F34A68150442BF23F069 +:1012D000070503F0070343EA4503E3608B6843F027 +:1012E00040036360CB68510543F00103A36042F4FF +:1012F000967343F0010323604FF0FF33236205D55B +:1013000012F0102205D0B2F1805F04D080F8643072 +:1013100030BD7F23FAE73F23F8E700BF784000089D +:10132000402600200044025800F1604300F01F02F4 +:101330000901400903F56143C9B2800083F8001335 +:10134000012300F16040934000F56140C0F8803116 +:1013500003607047F8B51546826804460B46AA42FA +:1013600000D28568A1692669761AB54207D2184667 +:101370002A46FFF7C7FDA3692B44A3610DE011D9ED +:10138000AF1B32461846FFF7BDFD3A46E1683044D0 +:10139000FFF7B8FDE2683A44A261A36828465B1BE8 +:1013A000A360F8BD18462A46FFF7ACFDE368E4E702 +:1013B000836893422DE9F04104460F46154600D25A +:1013C000856860692669361AB54207D22A463946C9 +:1013D000FFF798FD63692B4463610EE013D9A5EB19 +:1013E000060832463946FFF78DFD4246B919E068D6 +:1013F000FFF788FDE26842446261A36828465B1BF0 +:10140000A360BDE8F0812A463946FFF77BFDE3681B +:10141000E2E7000010B50A440024C361029B0060AB :1014200040608460C160816141610261036210BDFE :1014300008B582694369934201D1826882B98268A2 :10144000013282605A1C42611970426903699A42F2 @@ -332,12 +332,12 @@ :1014A00070BD3146204600F073FE0028E2DA85F375 :1014B000118870BD2DE9F74F05460F4690469A46B4 :1014C000D0F81C90202686F311884FF0000B1446AC -:1014D00064B1224639462846FFF740FF034668B903 +:1014D00064B1224639462846FFF73CFF034668B907 :1014E0005146284600F054FE0028F1D0002383F333 :1014F0001188A8EB040003B0BDE8F08FB9F1000F2C :1015000003D001902846C847019B8BF31188E41A49 -:101510001F4486F31188DBE7C16081614161C361CB -:101520001144009B0060406082600161036270476B +:101510001F4486F31188DBE7C1608161416111449A +:10152000C361009B0060406082600161036270479C :10153000F8B504460E461746202383F31188A568A4 :10154000A5B1A368013BA36063695A1C62611E7068 :10155000236962699A4224BFE3686361E3690BB15E @@ -348,7 +348,7 @@ :1015A000C3688361002100F003FE204610BD4FF0A8 :1015B000FF3010BD2DE9F74F05460F4690469A467D :1015C000D0F81C90202686F311884FF0000B1446AB -:1015D00064B1224639462846FFF7EEFE034668B955 +:1015D00064B1224639462846FFF7EAFE034668B959 :1015E0005146284600F0D4FD0028F1D0002383F3B3 :1015F0001188A8EB040003B0BDE8F08FB9F1000F2B :1016000003D001902846C847019B8BF31188E41A48 @@ -358,96 +358,96 @@ :10164000B9BF00004FF0FF333830FFF7B3BF0000E1 :101650001430FFF709BF00004FF0FF311430FFF7DF :1016600003BF00003830FFF763BF00004FF0FF32C8 -:101670003830FFF75DBF000000207047FFF7D8BD8E +:101670003830FFF75DBF000000207047FFF7D4BD92 :10168000044B0360002343608360C3600123037441 -:10169000704700BF8440000810B52023044683F340 -:1016A0001188FFF7F3FD02232374002383F31188CD +:10169000704700BF9040000810B52023044683F334 +:1016A0001188FFF7EFFD02232374002383F31188D1 :1016B00010BD000038B5C36904460D461BB90421AE :1016C0000844FFF7A9FF294604F11400FFF7B0FE14 :1016D000002806DA201D4FF48061BDE83840FFF78E :1016E0009BBF38BD026843681143016003B11847CE :1016F0007047000013B5446BD4F894341A6811781D -:10170000042915D1217C022912D1197912890123CA -:101710008B4013420CD101A904F14C0001F08EFF63 -:10172000D4F89444019B21790246206800F0EAF93C -:1017300002B010BD143001F011BF00004FF0FF33B4 -:10174000143001F00BBF00004C3001F0E3BF00008B -:101750004FF0FF334C3001F0DDBF0000143001F0DA -:10176000DFBE00004FF0FF31143001F0D9BE0000A1 -:101770004C3001F0AFBF00004FF0FF324C3001F0B1 -:10178000A9BF0000D0F8942438B51368197804294B -:10179000054601D0012038BD017C0229FAD1127919 -:1017A0005C89012090400440F4D105F1140001F05F -:1017B00071FE02460028EDD0D5F894544FF48073A2 +:10170000042915D1217C022912D1197901231289CA +:101710008B4013420CD101A904F14C0001F090FF61 +:10172000D4F894440246019B2179206800F0EAF93C +:1017300002B010BD143001F013BF00004FF0FF33B2 +:10174000143001F00DBF00004C3001F0E5BF000087 +:101750004FF0FF334C3001F0DFBF0000143001F0D8 +:10176000E1BE00004FF0FF31143001F0DBBE00009D +:101770004C3001F0B1BF00004FF0FF324C3001F0AF +:10178000ABBF0000D0F8942438B51368054619782B +:10179000042901D0012038BD017C0229FAD1127937 +:1017A00001205C8990400440F4D105F1140001F05F +:1017B00073FE02460028EDD0D5F894544FF48073A0 :1017C0002868697900F08CF9204638BD406BFFF736 :1017D000D9BF000000207047704700007FB5124B52 -:1017E0000360002343608360C360012502260F4B22 -:1017F000057404460290019300F184022946009684 -:101800004FF48073143001F021FE094B01930294D0 -:1018100000964FF4807304F52372294604F14C00BE -:1018200001F0E8FE04B070BDAC400008CD17000820 +:1017E00001250226044603600023057400F18402EB +:1017F000436029468360C3600C4B02901430019310 +:101800004FF48073009601F023FE094B04F5237218 +:101810002946019304F14C004FF480730294009622 +:1018200001F0EAFE04B070BDB8400008CD17000812 :10183000F51600080A68202383F311880B790B330F :1018400042F823004B79133342F823008B7913B10C -:101850000B3342F8230002230374C0F894140023CE +:101850000B3342F823000223C0F8941403740023CE :1018600083F311887047000038B5037F044613B135 -:1018700090F85430ABB9201D01250221FFF732FF4B +:1018700090F85430ABB90125201D0221FFF732FF4B :1018800004F1140025776FF0010100F09DFC84F84D :10189000545004F14C006FF00101BDE8384000F0F5 :1018A00093BC38BD10B5012104460430FFF71AFF80 :1018B0000023237784F8543010BD000038B5044667 -:1018C0000025143001F0DAFD04F14C00257701F019 -:1018D000A9FE201D84F854500121FFF703FF204684 +:1018C0000025143001F0DCFD04F14C00257701F017 +:1018D000ABFE201D84F854500121FFF703FF204682 :1018E000BDE83840FFF74EBF90F8803003F060034A :1018F000202B19D190F88120212A0AD0222A4FF0DA :1019000000030ED0202A0FD1084A426707228267BF :1019100004E0064B4367072383670023C367012066 :10192000704743678367F9E7002070471C24002055 -:10193000D0F8943437B51A681178042904461AD1BE -:10194000017C022917D11979128901238B40134296 -:1019500011D100F14C05284601F024FF58B101A92E -:10196000284601F06BFED4F89444019B217902468D +:10193000D0F8943437B51A680446117804291AD1BE +:10194000017C022917D11979012312898B40134296 +:1019500011D100F14C05284601F026FF58B101A92C +:10196000284601F06DFED4F894440246019B21798B :10197000206800F0C7F803B030BD000001F10B0390 :10198000F7B550F8234005460E46F4B1202383F303 -:10199000118805EB8607201D0821FFF7A3FEFB68D1 -:1019A0005B691B684C3413B1204601F055FE01A958 -:1019B000204601F043FE024648B1019B31462846CD +:10199000118805EB8607201D08214C34FFF7A2FEB5 +:1019A000FB685B691B6813B1204601F057FE01A973 +:1019B000204601F045FE024648B1019B31462846CB :1019C00000F0A0F8002383F3118803B0F0BDFB689A :1019D0005A691268002AF5D01B8A013B1340F1D1E5 :1019E00005F18002EAE70000133138B550F82140D4 :1019F000DCB1202383F31188D4F89424136852793E :101A000003EB8203DB689B695D6845B104216018C4 -:101A1000FFF768FE294604F1140001F045FD204659 +:101A1000FFF768FE294604F1140001F047FD204657 :101A2000FFF7B0FE002383F3118838BD7047000034 -:101A300001F040B8012303700023436000F130023D -:101A400000F1500142F8043B8A42D361FAD103818C +:101A300001F042B8012300F1300200F150010370BF +:101A40000023436042F8043B8A42D361FAD1038108 :101A50004381704738B50446202383F3118800255D -:101A6000416000F10C0300F1300243F8045B934243 -:101A7000FBD1204601F040F80223237085F3118842 -:101A800038BD000070B500EB810305465069DA608F -:101A90000E46144618B110220021FFF761FAA06922 -:101AA00018B110220021FFF75BFA31462846BDE845 -:101AB000704001F033B90000038903F00103038192 -:101AC000438903F00103438100F1300200F1100368 -:101AD000002143F8041B9342FBD101F0B7B9000089 -:101AE000F0B400EB81044789E4680125A4698D40C6 -:101AF0003D43458123600023A2606360F0BC01F098 -:101B0000D3B90000F0B400EB81040789E468012533 -:101B100064698D403D43058123600023A2606360BA -:101B2000F0BC01F04BBA0000022310B50370002393 -:101B30000446A0F8883080F88A3080F88B30038122 -:101B4000438100F10C0200F1300142F8043B8A426B -:101B5000FBD184F87030204601F074F863681B688C +:101A600000F10C0300F13002416043F8045B934243 +:101A7000FBD1204601F042F80223237085F3118840 +:101A800038BD000070B500EB8103054650690E4675 +:101A90001446DA6018B110220021FFF75BFAA06942 +:101AA00018B110220021FFF755FA31462846BDE84B +:101AB000704001F035B90000038900F130020021C7 +:101AC00003F001030381438903F00103438100F123 +:101AD000100343F8041B9342FBD101F0B9B9000095 +:101AE000F0B4012500EB810447898D40E4683D4353 +:101AF000A469458123600023A2606360F0BC01F00B +:101B0000D5B90000F0B4012500EB810407898D40B0 +:101B1000E4683D436469058123600023A26063603B +:101B2000F0BC01F04DBA0000022300F10C0200F1FC +:101B3000300110B5037004460023A0F8883080F807 +:101B40008A3080F88B300381438142F8043B8A421B +:101B5000FBD184F87030204601F076F863681B688A :101B600023B120460021BDE81040184710BD0000F9 -:101B7000436802781B6880F88C20052202700BB144 +:101B70000278436880F88C2005221B6802700BB144 :101B80000421184770470000436890F88C201B68B8 :101B900002700BB1052118477047000090F87030B3 :101BA00070B5044613B1002380F8703004F1800250 -:101BB000204601F06FF963689B6863BB94F880501E +:101BB000204601F071F963689B6863BB94F880501C :101BC00015F0600615D194F8813005F07F0545EADF :101BD000032540F202339D4200F00E815BD8022DB6 :101BE00000F0DC803FD8002D00F08780012D00F050 -:101BF000CF800021204601F005FC0021204601F0A5 -:101C0000F5FB63681B6813B106212046984706233D +:101BF000CF800021204601F007FC0021204601F0A3 +:101C0000F7FB63681B6813B106212046984706233B :101C100084F8703070BD204698470028CED094F8E4 :101C2000872094F8863043EA0223A26F934238BF9C :101C3000A36794F98030A56F002B4FF0200380F24A @@ -458,79 +458,79 @@ :101C8000B7D1B4F8883023F00203A4F8883066672F :101C9000A667E667C3E740F201639D421ED8B5F52B :101CA000C06F3BD2B5F5A06FA3D1B4F88030B3F5C7 -:101CB000A06F0ED194F8823084F88A30204601F06B -:101CC0001FF863681B6813B101212046984703235E +:101CB000A06F0ED194F88230204684F88A3001F06B +:101CC00021F863681B6813B101212046984703235C :101CD000237000236367A367E367A0E7B5F5106F80 :101CE00032D040F602439D4252D0B5F5006F80D10C -:101CF00004F18B036367012324E004F18803636725 -:101D00000223A367E5678AE794F88230012B7FF40A +:101CF00004F18B036367012324E004F18803E567A3 +:101D000063670223A3678AE794F88230012B7FF48C :101D100070AFB4F8883043F00203B6E794F885203A -:101D2000616894F884304D6894F8831043EA022384 -:101D3000204694F88220A84700283FF45AAF436811 +:101D20002046616894F884304D6843EA022394F8B1 +:101D3000831094F88220A84700283FF45AAF4368E4 :101D400063670368A367A4E72378042B10D12023DB :101D500083F311882046FFF7AFFE86F3118863688E -:101D600084F88B601B68032121700BB120469847D3 +:101D6000032184F88B601B6821700BB120469847D3 :101D700094F88230002BACD084F88B30042323708D :101D800063681B68002BA4D0022120469847A0E777 :101D9000374B63670223A36700239DE794F8841001 -:101DA00011F0800F204601F00F010ED001F064F811 -:101DB000012806D002287FF41CAF2E4B6367A06772 -:101DC00067E72D4B6367A56763E701F047F8EFE727 +:101DA000204611F0800F01F00F010ED001F066F80F +:101DB000012806D002287FF41CAF2E4BA067636772 +:101DC00067E72D4BA567636763E701F049F8EFE725 :101DD00094F88230002B7FF40CAF94F8843013F029 -:101DE0000F013FF476AF1A06204602D501F022FB20 -:101DF0006FE701F013FB6CE794F88230002B7FF45F +:101DE0000F013FF476AF1A06204602D501F024FB1E +:101DF0006FE701F015FB6CE794F88230002B7FF45D :101E0000F8AE94F8843013F00F013FF462AF1B0674 -:101E1000204602D501F0F6FA5BE701F0E7FA58E751 +:101E1000204602D501F0F8FA5BE701F0E9FA58E74D :101E2000142284F8702083F311882B462A46294611 :101E30002046FFF755FE85F3118870BD5DB1152270 :101E400084F8702083F311880021A36F626F20460D :101E5000FFF746FE03E70B2284F8702083F3118816 :101E60002B462A4629462046FFF74CFEE3E700BFF3 -:101E7000DC400008D4400008D840000838B590F88D +:101E7000E8400008E0400008E440000838B590F869 :101E800070300446152B29D8DFE803F03E282828B7 :101E900028283E28280B29392828282828282828B7 :101EA0003E3E90F8871090F88620836F42EA012228 :101EB0009A4214D9C268128AB3FBF2F502FB1535B7 :101EC0006DB9202383F311882B462A462946FFF754 :101ED00019FE85F311880A2384F8703038BD142365 -:101EE00084F87030202383F3118800231A461946A2 -:101EF0002046FFF7F5FD002383F3118838BDC36F3B -:101F000003B198470023E7E7002101F07BFA0021A5 -:101F1000204601F06BFA63681B6813B10621204666 +:101EE00084F87030202383F31188002320461A469B +:101EF0001946FFF7F5FD002383F3118838BDC36F42 +:101F000003B198470023E7E7002101F07DFA0021A3 +:101F1000204601F06DFA63681B6813B10621204664 :101F200098470623D8E7000090F87020152A38B5A6 :101F3000044622D80123934040F6416213421DD14A :101F400013F480150FD19B0217D50B2380F8703046 :101F5000202383F311882B462A462946FFF7D2FD1A :101F600085F3118838BDC3689B695B682BB9C36F63 :101F700003B19847002384F8703038BD002101F088 -:101F800041FA0021204601F031FA63681B6813B161 +:101F800043FA0021204601F033FA63681B6813B15D :101F90000621204698470623EDE70000024B002269 -:101FA0001B605B609A607047AC2A002000230374BA -:101FB0008268054B1B6899689142FBD25A6803609E +:101FA0001B605B609A607047AC2A00200023826847 +:101FB0000374054B1B6899689142FBD25A68036011 :101FC0004260106058607047AC2A002008B520239A :101FD00083F31188037C032B05D0042B0DD02BB980 :101FE00083F3118808BD436900221A604FF0FF3364 :101FF0004361FFF7DBFF0023F2E790E80C001A6073 -:1020000002685360F2E70000002303748268054B06 +:1020000002685360F2E70000002382680374054B06 :102010001B6899689142FBD85A680360426010605F :1020200058607047AC2A0020054B1969087418687D -:1020300002681A605360186101230374FEF7C4B983 -:10204000AC2A002030B54B1C87B005460A4C10D096 -:1020500023690A4A01A800F0D3F82846FFF7E4FFF5 +:10203000026853601A60186101230374FEF7C4B983 +:10204000AC2A00204B1C30B5054687B00A4C10D096 +:10205000236901A8094A00F0D3F82846FFF7E4FFF6 :10206000049B13B101A800F007F92369586907B070 :1020700030BDFFF7D9FFF8E7AC2A0020CD1F0008DC -:1020800038B50C4D41612B6981689A6891420446CC +:1020800038B50C4D044641612B6981689A689142CC :1020900003D8BDE83840FFF789BF1846FFF786FF31 :1020A00001232C61014623742046BDE83840FEF729 :1020B0008BB900BFAC2A0020044B1A681B699068DA :1020C0009B68984294BF002001207047AC2A0020F2 -:1020D00010B5084C236820691A68226054600122F8 +:1020D00010B5084C236820691A68546022600122F8 :1020E00023611A74FFF790FF01462069BDE8104094 :1020F000FEF76AB9AC2A0020826002220274002234 :10210000427470478368A3F17C0243F80C2C026987 :1021100043F83C2C426943F8382C074A43F81C2CFE -:10212000C26843F8102C022203F8082C002203F89E -:10213000072CA3F118007047E103000810B5202315 +:10212000C268A3F1180043F8102C022203F8082C0F +:10213000002203F8072C7047E103000810B52023A4 :1021400083F31188FFF7DEFF00210446FFF798FFB5 :10215000002383F31188204610BD0000024B1B6949 :1021600058610F20FFF760BFAC2A0020202383F3C3 @@ -538,386 +538,386 @@ :1021800011880820FFF75EFF002383F3118808BD44 :1021900049B1064B42681B6918605A60136043607E :1021A0000420FFF74FBF4FF0FF307047AC2A0020EC -:1021B0000368984206D01A68026050605961184658 +:1021B0000368984206D01A68026050601846596158 :1021C000FFF7F4BE7047000038B504460D4620689E :1021D000844200D138BD036823605C604561FFF72D :1021E000E5FEF4E7054B03F114025A619A614FF0E2 :1021F000FF32DA6100221A62704700BFAC2A002069 -:10220000F8B503611A4BC2605C6A1A4B1A46022980 -:1022100052F8145F38BF0221954206461F460AD184 +:10220000F8B5036102291A4B0646C26038BF0221A5 +:102210005C6A184B1A461F4652F8145F95420AD161 :10222000586198611C620560456081600819BDE8CD -:10223000F84001F0D9BA186AAB68241A0C1902D315 -:10224000E41A2D6804E09C4202D2204401F0DCFA3A -:10225000AB689C42F4D86B68736035601E606E603A -:10226000B460A9684FF0FF33091BA960FB61F8BD9A +:10223000F84001F0DBBA186AAB68241A0C1902D313 +:10224000E41A2D6804E09C4202D2204401F0DEFA38 +:10225000AB689C42F4D86B68356073601E604FF0C9 +:10226000FF336E60B460A968091BA960FB61F8BD0B :10227000000C0040AC2A002010B41A4C234653F83E :10228000141F814210D0416802680A6002685160E0 :102290009A424FF00001C16003D0936881680B44FB -:1022A00093605DF8044B70470A68626100209A42AF -:1022B0005360C86003D15DF8044B01F09FBA936886 -:1022C000886803449360084A206A526A121A93424B -:1022D000E7D9991A012998BF931C18445DF8044B5B -:1022E00001F092BAAC2A0020000C00400020704798 +:1022A00093605DF8044B70470A6800209A426261AF +:1022B0005360C86003D15DF8044B01F0A1BA936884 +:1022C00088680344206A9360074A526A121A93424C +:1022D000E7D9991A5DF8044B012998BF931C18445B +:1022E00001F094BAAC2A0020000C00400020704796 :1022F000FEE70000704700004FF0FF30704700001D :10230000022906D0032906D00129064818BF00205B :10231000704705487047032A9ABF044800EBC20083 -:1023200000207047B04100086441000824240020C8 -:1023300070B59AB001AD064608462946144600F02D -:1023400095F82846FEF704FEC0B2431C5B0086E801 -:102350001800237003236370002302341946DAB295 -:10236000904204F1020401D81AB070BDEA5C04F88E -:10237000022C04F8011C0133F1E7000008B520230A +:1023200000207047BC4100087041000824240020B0 +:1023300070B59AB006460846144601AD294600F02D +:1023400095F82846FEF7FEFDC0B2431C5B0086E808 +:10235000180023700323023404F8013C00231946BB +:10236000DAB20234904201D81AB070BDEA5C01338F +:1023700004F8011C04F8022CF2E7000008B5202341 :1023800083F311880348FFF7D3FA002383F31188FE :1023900008BD00BFEC2A002010B50446052916D858 :1023A000DFE801F016150316161D202383F31188AC :1023B0000E4A0121FFF766FB20460D4A0221FFF776 :1023C00061FB0C48FFF77AFA002383F3118810BDF4 :1023D000202383F311880748FFF746FAF4E7202308 -:1023E00083F311880348FFF75DFAEDE7E04000084A -:1023F00004410008EC2A002038B50C4D0C4C0D4966 -:102400002A4604F10800FFF793FF05F1CA0204F120 +:1023E00083F311880348FFF75DFAEDE7EC4000083E +:1023F00010410008EC2A002038B50C4D0C4C2A4640 +:102400000C4904F10800FFF793FF05F1CA0204F13B :1024100010000949FFF78CFF05F5CA7204F1180096 :102420000649BDE83840FFF783BF00BFB42F002046 -:1024300024240020304100083D4100084B410008A1 -:1024400070B5044608460D46FEF782FDC6B220462A +:10243000242400203C41000849410008574100087D +:1024400070B5044608460D46FEF77CFDC6B2204630 :10245000013403780BB9184670BD32462946FEF7A1 -:102460005FFD0028F3D1012070BD00002DE9F84F79 -:1024700005460C46FEF76CFD2B49C6B22846FFF711 -:10248000DFFF08B10336F6B228492846FFF7D8FF28 -:1024900008B11036F6B2632E0DD8DFF88C80DFF865 -:1024A0008C90234FDFF890A0DFF890B02E7846B9DB +:102460005BFD0028F3D1012070BD00002DE9F84F7D +:1024700005460C46FEF766FD2C49C6B22846FFF716 +:10248000DFFF08B10336F6B229492846FFF7D8FF27 +:1024900008B11036F6B2632E0DD8DFF89080DFF861 +:1024A0009090244FDFF894A0DFF894B02E7846B9CE :1024B0002670BDE8F88F29462046BDE8F84F01F0A8 -:1024C000AFBD252E2CD1072241462846FEF728FD18 -:1024D00058B9DBF800302360DBF804306360BBF8E8 -:1024E0000830238107350A34E0E7082249462846A8 -:1024F000FEF716FDA0B90F4BA21C13F8011F090926 -:102500005345C95D02F8021C197801F00F0102F170 -:102510000202C95D02F8031CEFD118340835C5E783 -:10252000267001350134C1E7D04100084B41000855 -:10253000E3410008FFE7F11F0BE8F11FD841000855 -:10254000BFF34F8F044B1A695107FCD1D3F8102108 -:102550005207F8D1704700BF0020005208B50D4B5C -:102560001B78ABB9FFF7ECFF0B4BDA68D10741BF23 -:102570000A4A5A6002F188325A60D3F80C21D20715 -:1025800041BF064AC3F8042102F18832C3F804218E -:1025900008BD00BF12320020002000522301674511 -:1025A00008B5114B1B78F3B9104B1A69510742BF9C -:1025B000DA6842F04002DA60D3F81021520742BFD5 -:1025C000D3F80C2142F04002C3F80C21FFF7B8FF0A -:1025D000064BDA6842F00102DA60D3F80C2142F0CF -:1025E0000102C3F80C2108BD123200200020005265 -:1025F0000F289ABF00F5806040040020704700005B -:102600004FF4003070470000102070470F2808B5C5 -:102610000BD8FFF7EDFF00F500330268013204D15B -:1026200004308342F9D1012008BD002008BD00001C -:102630000F2810B504463FD8FFF782FFFFF78EFF43 -:102640001E484FF0FF33072C4361C0F814311DD8EA -:102650000361FFF775FF230243F02403C360C368DF -:1026600043F08003C36003695A07FCD4FFF768FF97 -:102670002046FFF7BDFF4FF4003100F0EDF8FFF703 -:102680008FFF2046BDE81040FFF7C0BFC0F81031F3 -:10269000FFF756FFA4F108031B0243F02403C0F820 -:1026A0000C31D0F80C3143F08003C0F80C31D0F875 -:1026B00010315B07FBD4D9E7002010BD0020005289 -:1026C0002DE9F84F40EA0203DB06064688469146AC -:1026D0004AD1FFF743FFDFF8B0B04546A9EB050349 -:1026E00043441F2B04D8FFF75BFF0120BDE8F88FA0 -:1026F000204A2148214F06F178439342204B214A3A -:1027000098BF9A4603F1FC0386BF1F46924658467F -:10271000FFF716FF4FF0FF3303603B6843F00203FF -:102720003B6005F11C022B1FA6EB050EDAF80040FA -:1027300014F00504FAD153F8041F4EF80310934225 -:10274000F4D1BFF34F8FFFF7FBFE4FF0FF33036071 -:102750003B6823F002033B6020222946304601F00B -:102760004FFC20B1FFF71CFF0020BDE8F88F20369A -:102770002035B3E7FFFF0F00142100520C20005258 -:1027800010200052102100521420005210B5084CA5 -:10279000237828B153B9FFF7E1FE0123237010BD60 -:1027A00023B12070BDE81040FFF7FABE10BD00BF96 -:1027B0001232002010B50244064B0439D2B29042C6 -:1027C00000D110BD441C00B253F8200041F8040FA2 -:1027D000E0B2F4E7504000580F4B30B51C6F2404B2 -:1027E00005D41C6F1C671C6F44F400441C670B4C21 -:1027F000236843F4807323600244094B0439D2B246 -:10280000904200D130BD441C00B251F8045F43F83F -:102810002050E0B2F4E700BF0044025800480258DC -:102820005040005807B5012201A90020FFF7C2FF60 -:10283000019803B05DF804FB13B50446FFF7F2FFFF -:10284000A04206D002A9012241F8044D0020FFF762 -:10285000C3FF02B010BD00000144BFF34F8F064B11 -:10286000884204D3BFF34F8FBFF36F8F7047C3F815 -:102870005C022030F4E700BF00ED00E0034B1B6872 -:102880005B0142BF024B01221A707047D0440258CC -:1028900013320020014B1878704700BF133200201C -:1028A000064A536823F001035360EFF3098368334A -:1028B00083F30988002383F31188704730EF00E029 -:1028C00010B5202383F31188104B5B6813F4006369 -:1028D00018D0F1EE103AEFF309844FF0807344F80A -:1028E0004C3C0B4BDB6844F8083CA4F1680383F3D1 -:1028F0000988FFF7E1FB18B1064B44F8503C10BDC6 -:10290000054BFAE783F3118810BD00BF00ED00E02E -:1029100030EF00E0F1030008F4030008F0B5BFF366 -:102920004F8FBFF36F8F1D4B0021C3F85012BFF3C1 -:102930004F8FBFF36F8F5A6942F400325A61BFF371 -:102940004F8FBFF36F8FC3F88410BFF34F8FD3F84F -:102950008020C2F3C904C2F34E325201A50743F6E8 -:10296000E07602EA060E284621464EEA00070139C3 -:10297000C3F860724F1C00F14040F6D1203A12F1CA -:10298000200FEED1BFF34F8F5A6942F480325A6163 -:10299000BFF34F8FBFF36F8FF0BD00BF00ED00E0BE -:1029A000FEE70000084A094B09498B4204D3094A53 -:1029B0000021934205D3704752F8040F43F8040BEB -:1029C000F3E743F8041BF4E7D04300086035002028 -:1029D0006035002060350020D0F8943030B50022FA -:1029E0009D68D0F8904011464FF0FF3004EB421341 -:1029F00001329542C3F80019C3F81019C3F8080949 -:102A0000C3F8001BC3F8101BC3F8080BEED24FF03D -:102A10000113C4F81C3830BD00EB81032DE9F04FE1 -:102A2000D3F80CE0DEF814404F1CD4F800C03F038C -:102A30004FEA41186568D0F8902065450AD3D2F86E -:102A40003438012000FA01F123EA0101C2F83418F8 -:102A5000BDE8F08FBEF81060ACEB0503B34228BFB1 -:102A6000334602EB0806D6F81869B6B2B3EB860F08 -:102A700013D8A6683A44A6F1040A99465AF804BF46 -:102A8000C2F800B0B9F1040F02D9A9F10409F5E7C1 -:102A90001E442B44A6606360CCE70020BDE8F08FA5 -:102AA000890141F02001016103699B06FCD41220D9 -:102AB00000F03CBF10B50A4C2046FEF7BBFF094BA7 -:102AC000C4F89030084BC4F89430084C2046FEF708 -:102AD000B1FF074BC4F89030064BC4F8943010BDDA -:102AE000143200200000084018420008B0320020D4 -:102AF00000000440244200080378012B70B505460D -:102B00005DD1494BD0F89040984259D1474BD3F80A -:102B1000D82042F00062C3F8D820D3F8002142F058 -:102B20000062C3F80021D3F80021D3F8802042F0DE -:102B30000062C3F88020D3F8802022F00062C3F83E -:102B40008020D3F880300E216520FEF7F1FB384B52 -:102B5000E360384BC4F800380023C4F8003EC023BB -:102B60002360D5F890604FF40413A3633369002BFE -:102B7000FCDA012333610C2000F0D8FE3369DB0757 -:102B8000FCD4122000F0D2FE3369002BFCDA0026C0 -:102B9000A6602846FFF720FF6B68C4F81068DB6862 -:102BA000C4F81468C4F81C68002B3AD1224BA36106 -:102BB0004FF0FF336361A36843F00103A36070BD6E -:102BC0001E4B9842C8D1194BD3F8D82042F000725E -:102BD000C3F8D820D3F8002142F00072C3F80021D6 -:102BE000D3F80021D3F8802042F00072C3F880208F -:102BF000D3F8802022F00072C3F88020D3F8802020 -:102C0000D3F8D82022F08062C3F8D820D3F800216E -:102C100022F08062C3F80021D3F800310E214D204C -:102C200093E7074BC3E700BF14320020004402586B -:102C30004014004003002002003C30C0B0320020AD -:102C4000083C30C0F8B5D0F8904005460021204639 -:102C5000FFF726FFD5F8941000234FF001128F687C -:102C6000C4F834384FF00066C4F81C284FF0FF3029 -:102C700004EB431201339F42C2F80069C2F8006BB3 -:102C8000C2F80809C2F8080BF2D20B68D5F89020F8 -:102C9000C5F89830636210231361166916F01006A8 -:102CA000FBD1122000F042FED4F8003823F4FE637A -:102CB000C4F80038A36943F4402343F01003A36130 -:102CC0000923C4F81038C4F814380B4BEB604FF0EC -:102CD000C043C4F8103B094BC4F8003BC4F810696A -:102CE000C4F80039D5F8983003F1100243F480138A -:102CF000C5F89820A362F8BDF44100084080001098 -:102D0000D0F8902090F88A10D2F8003823F4FE63AF -:102D100043EA0113C2F80038704700002DE9F04182 -:102D20000EB200EB86080D46D8F80C100F6807F0BD -:102D30000303022B53D0032B53D03F4A3F4F012BA9 -:102D400018BF1746D0F890404FEA451E04EB0E031B -:102D50000022C3F8102B8A6905F1100C002A42D01A -:102D60004A8A05F158035B013A43E2500123D4F843 -:102D70001C2803FA0CF31343A6444A69C4F81C3810 -:102D80000023CEF8103905F13F03002A3BD00A8A10 -:102D9000898B9208012988BF4A43D0F8981004EB28 -:102DA0008303561841EA0242C0F8986029465A60E7 -:102DB0002046FFF775FED8F80C301B8A43EA85538E -:102DC0001F4305F148035B01E7500123D4F81C2899 -:102DD00003FA05F51543C4F81C58BDE8F081184FF7 -:102DE000B0E7184FAEE704EB4613D3F8002B22F4FC -:102DF0000042C3F8002BD4F81C28012303FA0CF37B -:102E000022EA0303B8E704EB83030F4A5A6004EB9A -:102E1000461629462046FFF743FED6F8003923F42C -:102E20000043C6F80039D4F81C38012202FA05F52F -:102E300023EA0505CFE700BF0080001000800410E2 -:102E40000080081000800C1000040002D0F89420CC -:102E50001268C0F89820FFF7BFBD00005831D0F8C5 -:102E6000903049015B5813F4004004D013F4001F64 -:102E700014BF0120022070474831D0F8903049013A -:102E80005B5813F4004004D013F4001F14BF01205A -:102E90000220704700EB8101CB68196A0B68136050 -:102EA0004B6853607047000000EB810330B5DD686C -:102EB000AA691368D36019B9402B84BF40231360FB -:102EC0006B8A1468D0F890201C44013CB4FBF3F4E6 -:102ED0006343033323F0030302EB411043EAC4438B -:102EE00043F0C043C0F8103B2B6803F00303012BF1 -:102EF00009B20ED1D2F8083802EB411013F4807FEA -:102F0000D0F8003B14BF43F0805343F00053C0F8A7 -:102F1000003B02EB4112D2F8003B43F00443C2F8FD -:102F2000003B30BD2DE9F041D0F8906006EB411335 -:102F30000546D3F8087BC3F8087B3A070C4608D54A -:102F4000D6F814381B0704D500EB8103DB685B68F7 -:102F50009847FA072FD5D6F81438DB072BD505EBA1 -:102F60008403D968CCB98B69488A5E68B6FBF0F2F5 -:102F700000FB12628AB91868DA6890420DD2121A00 -:102F800083E81400202383F3118821462846FFF7A5 -:102F90008BFF84F31188BDE8F081012303FA04F26A -:102FA0006B8923EA02036B81CB6823B12146284653 -:102FB000BDE8F0411847BDE8F081000000EB810357 -:102FC00070B5DD68D0F890306C692668E6604A011B -:102FD00056BB1A444FF40020C2F810092A6802F0C8 -:102FE0000302012A0AB20ED1D3F8080803EB4214F7 -:102FF00010F4807FD4F8000914BF40F0805040F0F6 -:103000000050C4F8000903EB4212D2F8000940F066 -:103010000440C2F80009D3F83408012202FA01F191 -:103020000143C3F8341870BD19B9402E84BF402045 -:10303000206020682E8A841940F00050013C1A4418 -:10304000B4FBF6F440EAC440C6E700002DE9F041C5 -:10305000D0F8906006EB41130446D3F80879C3F822 -:103060000879FB070D461CD5D6F81038DA0718D5B5 -:1030700000EB8103D3F80CE0DEF81430D3F800C085 -:10308000DA6894451BD2A2EB0C024FF000081A60DC -:10309000C3F80480202383F31188FFF78FFF88F3A0 -:1030A00011883B0618D5D6F834280123AB401342CB -:1030B00012D029462046BDE8F041FFF7ADBC012300 -:1030C00003FA01F2038923EA02030381DEF80830E0 -:1030D000002BE6D09847E4E7BDE8F0812DE9F04702 -:1030E000D0F890506E69AB691E40F10404466E61E1 -:1030F00003D5BDE8F047FEF717BD002E11DAD5F86D -:10310000003E9A071EBFD5F8003E23F00303C5F822 -:10311000003ED5F8043823F00103C5F80438FEF763 -:1031200033FD330502D52046FEF722FDB7040CD54A -:10313000D5F8083813F0060FEB6823F470530CBF72 -:1031400043F4105343F4A053EB60300704D5636895 -:10315000DB680BB120469847F10200F1A180B20272 -:103160000BD5D4F8908000274FF00109D4F89430A3 -:103170009B68F9B28B4280F0D280F3061AD5D4F85E -:1031800090100A6AC2F30A1702F00F0302F4F01259 -:10319000B2F5802F00F0EC80B2F5402F0AD104EB9D -:1031A000830301F58051DB68186A00231A469F42A9 -:1031B00040F0D1803003D5F8185835D5E90303D550 -:1031C00000212046FFF7AEFEAA0303D501212046C9 -:1031D000FFF7A8FE6B0303D502212046FFF7A2FEEE -:1031E0002F0303D503212046FFF79CFEE80203D5F9 -:1031F00004212046FFF796FEA90203D505212046AB -:10320000FFF790FE6A0203D506212046FFF78AFEEB -:103210002B0203D507212046FFF784FEEF0103D5DB -:1032200008212046FFF77EFE700340F1C980E907C0 -:1032300003D500212046FFF709FFAA0703D5012186 -:103240002046FFF703FF6B0703D502212046FFF757 -:10325000FDFE2F0703D503212046FFF7F7FEEE06FC -:1032600003D504212046FFF7F1FEA80603D505216A -:103270002046FFF7EBFE690603D506212046FFF73F -:10328000E5FE2A0603D507212046FFF7DFFEEB0502 -:1032900040F1968020460821BDE8F047FFF7D6BEF2 -:1032A000D4F890904FF000084FF0010AD4F8943011 -:1032B0009B685FFA88F7BB42FFF451AF09EB4713F5 -:1032C000D3F8002902F44022B2F5802F24D1D3F89C -:1032D0000029002A20DAD3F8002942F09042C3F8EE -:1032E0000029D3F80029002AFBDB3946D4F89000E6 -:1032F000FFF7D6FB22890AFA07F322EA03032381A8 -:1033000004EB8703DB689B6813B139462046984776 -:1033100039462046FFF780FB08F10108C6E708EBB5 -:103320004112D2F8003B03F44023B3F5802F10D1B3 -:10333000D2F8003B002B0CDA628909FA01F322EA89 -:103340000303638104EB8103DB68DB680BB1204678 -:10335000984701370AE713F0030F08BF0A68072BE5 -:1033600098BF027003F101039CBF120A01301EE7EF -:1033700004EB830301F58051DA6890690268D0F8A4 -:1033800008C04068A2EB000E00221046974208D108 -:10339000DB689B699A683A449A605A6817445F6090 -:1033A00008E712F0030F08BF0868964588BF8CF83D -:1033B000000002F1010284BF000A0CF1010CE5E7F4 -:1033C000BDE8F08708B50348FFF788FEBDE8084070 -:1033D000FFF776BA1432002008B50348FFF77EFEE7 -:1033E000BDE80840FFF76CBAB0320020D0F890304A -:1033F00003EB4111D1F8003B43F40013C1F8003B4B -:1034000070470000D0F8903003EB4111D1F800393B -:1034100043F40013C1F8003970470000D0F8903031 -:1034200003EB4111D1F8003B23F40013C1F8003B3A -:1034300070470000D0F8903003EB4111D1F800390B -:1034400023F40013C1F800397047000030B5039C25 -:103450000172043304FB0325C361049B0363002151 -:10346000059B00604060C160426102618561046249 -:1034700042628162C162436330BD00000022416A42 -:1034800041610161C2608262C2626FF00101FEF7B8 -:103490009BBE000003694269934203D1C2680AB12E -:1034A00000207047181D704703691960C268013217 -:1034B000C260C269134482690361934224BF436AB4 -:1034C00003610021FEF774BE38B504460D46E3687B -:1034D0003BB16269131D1268A3621344E3620020CA -:1034E00038BD237A33B929462046FEF751FE00281D -:1034F000EDDA38BD6FF00100FBE70000C368C26978 -:10350000013BC3604369134482694361934224BF12 -:10351000436A436100238362036B03B1184770471A -:1035200070B52023044683F31188866A3EB9FFF7FD -:10353000CBFF054618B186F31188284670BDA36AF3 -:10354000E26A13F8015BA362934202D32046FFF7BD -:10355000D5FF002383F31188EFE700002DE9F84F32 -:1035600004460E4690469946202787F31188002589 -:10357000AA46D4F828B0BBF1000F09D1494620462D -:10358000FFF7A2FF20B18BF311882846BDE8F88F22 -:10359000A16AE36AA8EB050B5B1A9B4528BF9B4613 -:1035A000BBF1400F1BD9334601F1400251F8040B27 -:1035B00043F8040B9142F9D1A36A40334036A36229 -:1035C0004035A26AE36A9A4202D32046FFF796FF8B -:1035D0008AF311884545D8D287F31188C9E7304668 -:1035E0005A46FDF793FCA36A5B445E44A3625D44C4 -:1035F000E7E7000010B5029C0172043303FB0421CD -:10360000C36100238362C362039B0363049B006066 -:103610004060C4604261026181610462426243634E -:1036200010BD0000026AC260426A4261026100226B -:103630008262C2626FF00101FEF7C6BD4369026992 -:103640009A4203D1C2680AB100207047184650F868 -:10365000043B0B6070470000C368C2690133C3605C -:103660004369134482694361934224BF436A4361BF -:103670000021FEF79DBD000038B504460D46E36805 -:103680003BB123691A1DA262E2691344E362002080 -:1036900038BD237A33B929462046FEF779FD002844 -:1036A000EDDA38BD6FF00100FBE700000369196037 -:1036B000C268013AC260C2691344826903619342DD -:1036C00024BF436A036100238362036B03B118477D -:1036D0007047000070B5202304460E4683F311881E -:1036E000856A35B91146FFF7C7FF10B185F3118818 -:1036F00070BDA36A1E70A36AE26A01339342A3629B -:1037000004D3E16920460439FFF7D0FF002080F39D -:10371000118870BD2DE9F84F04460D4691469A4632 -:103720004FF0200888F311880026B346A76A4FB9E6 -:1037300051462046FFF7A0FF20B187F3118830469D -:10374000BDE8F88FA06AE76AA9EB06033F1A9F421B -:1037500028BF1F46402F1BD905F1400355F8042B05 -:1037600040F8042B9D42F9D1A36A4033A36240364E -:10377000A26AE36A9A4204D3E16920460439FFF75A -:1037800095FF8BF311884E45D9D288F31188CDE788 -:1037900029463A46FDF7BAFBA36A3B443D44A3627F -:1037A0003E44E5E7026943699A4203D1C3681BB905 -:1037B000184670470023FBE7836A002BF8D0043BD0 -:1037C0009B1AF5D01360C368013BC360C3691A44F8 -:1037D000836902619A4224BF436A036100238362C2 -:1037E0000123E5E700F052B9034B002258631A6148 -:1037F0000222DA60704700BF000C0040014B00223B -:10380000DA607047000C0040014B5863704700BFFE -:10381000000C0040FEE7000010B5194CFEF7BEFB9F -:10382000FEF7E0FC802217492046FEF765FC0123E5 -:1038300044F8180C0374144B144AD96821F4E0615D -:103840000904090C0A431249DA60CA6842F080721E -:10385000CA60104A1049C2F8B01F116841F0010156 -:1038600011601022DA77202283F82220002383F3CC -:10387000118862B60948BDE81040FEF75FBC00BF82 -:10388000D42A00203042000800ED00E00003FA05D1 -:10389000F0ED00E0001000E055CEACC53842000865 -:1038A0002DE9F84F1F4CDFF88090656904F114078B -:1038B0004FF00008D9F82430266AAA689E1B964269 -:1038C0001DD34FF0200AAA68236AD5F80CB0134420 -:1038D00023622B68BB425F60A6EB02066361C5F8FA -:1038E0000C8001D1FFF78AFF88F311882869D84737 -:1038F0008AF311886569AB689E42E4D2DAE76269AF -:10390000BA420CD0916823628E1B9660A868022888 -:103910002CBF1818981CBDE8F84FFFF775BFBDE81D -:10392000F88F00BFAC2A0020000C0040034B596800 +:1024C000B5BD252E2ED1072241462846FEF724FD14 +:1024D00070B9DBF8003007350A3444F80A3CDBF801 +:1024E000043044F8063CBBF8083024F8023CDDE731 +:1024F000082249462846FEF70FFD98B9A21C0E4B4C +:1025000013F8011F023209095345C95D02F8041C82 +:10251000197801F00F01C95D02F8031CF0D11834DD +:102520000835C3E7267001350134BFE7DC410008F8 +:1025300057410008EF410008FFE7F11F0BE8F11FCA +:10254000E4410008BFF34F8F044B1A695107FCD1D7 +:10255000D3F810215207F8D1704700BF0020005275 +:1025600008B50D4B1B78ABB9FFF7ECFF0B4BDA68E6 +:10257000D10704D50A4A5A6002F188325A60D3F86A +:102580000C21D20706D5064AC3F8042102F188328D +:10259000C3F8042108BD00BF123200200020005201 +:1025A0002301674508B5114B1B78F3B9104B1A6925 +:1025B000510703D5DA6842F04002DA60D3F81021FF +:1025C000520705D5D3F80C2142F04002C3F80C2184 +:1025D000FFF7B8FF064BDA6842F00102DA60D3F881 +:1025E0000C2142F00102C3F80C2108BD1232002078 +:1025F000002000520F289ABF00F5806040040020A0 +:10260000704700004FF40030704700001020704702 +:102610000F2808B50BD8FFF7EDFF00F5003302686F +:10262000013204D104308342F9D1012008BD0020D9 +:1026300008BD00000F2810B504463FD8FFF782FF01 +:10264000FFF78EFF1E484FF0FF33072C4361C0F8A1 +:1026500014311DD80361FFF775FF230243F02403F3 +:10266000C360C36843F08003C36003695A07FCD4A6 +:10267000FFF768FF2046FFF7BDFF4FF4003100F081 +:10268000EDF8FFF78FFF2046BDE81040FFF7C0BF11 +:10269000C0F81031FFF756FFA4F108031B0243F006 +:1026A0002403C0F80C31D0F80C3143F08003C0F89B +:1026B0000C31D0F810315B07FBD4D9E7002010BDF6 +:1026C000002000522DE9F84F40EA020306468846F2 +:1026D0009146DB064AD14546DFF8B0B0FFF740FF30 +:1026E000A9EB050343441F2B04D8FFF75BFF012030 +:1026F000BDE8F88F06F178431F4A20489342204BEB +:10270000204A98BF9A4603F1FC031F4F86BF9246AA +:102710001F465846FFF716FF4FF0FF3305F11C0226 +:10272000A6EB050E03603B6843F002033B602B1FE2 +:10273000DAF8004014F00504FAD153F8041F93426C +:102740004EF80310F4D1BFF34F8FFFF7FBFE4FF0AD +:10275000FF3320222946036030463B6823F0020302 +:102760003B6001F053FC20B1FFF71CFF0020BDE8E7 +:10277000F88F20362035B3E7FFFF0F0014210052F9 +:1027800010200052102100520C2000521420005240 +:1027900010B5084C237828B153B9FFF7E1FE0123A7 +:1027A000237010BD23B12070BDE81040FFF7FABEC2 +:1027B00010BD00BF1232002002440439064BD2B2D1 +:1027C00010B5904200D110BD441C00B253F8200057 +:1027D00041F8040FE0B2F4E7504000580F4B30B519 +:1027E0001C6F240405D41C6F1C671C6F44F4004448 +:1027F0001C670B4C024404392368D2B243F4807343 +:102800002360084B904200D130BD441C51F8045F56 +:1028100000B243F82050E0B2F4E700BF0044025891 +:10282000004802585040005807B5012201A9002075 +:10283000FFF7C2FF019803B05DF804FB13B504462F +:10284000FFF7F2FFA04206D002A90122002041F8C2 +:10285000044DFFF7C3FF02B010BD00000144BFF3F9 +:102860004F8F064B884204D3BFF34F8FBFF36F8F58 +:102870007047C3F85C022030F4E700BF00ED00E0D1 +:10288000034B1B685B0142BF0122024B1A70704769 +:10289000D044025813320020014B1878704700BF13 +:1028A00013320020064A536823F001035360EFF30C +:1028B0000983683383F30988002383F31188704701 +:1028C00030EF00E010B5202383F31188104B5B68D4 +:1028D00013F4006318D0F1EE103AEFF309844FF0CF +:1028E000807344F84C3C0B4BDB6844F8083CA4F183 +:1028F000680383F30988FFF7DFFB18B1064B44F840 +:10290000503C10BD054BFAE783F3118810BD00BFA2 +:1029100000ED00E030EF00E0F1030008F4030008F0 +:10292000F0B5BFF34F8FBFF36F8F1D4B0021C3F87E +:102930005012BFF34F8FBFF36F8F5A6942F40032CA +:102940005A61BFF34F8FBFF36F8FC3F88410BFF38B +:102950004F8FD3F8802043F6E076C2F3C904C2F368 +:102960004E32A507520102EA060E284621464EEADB +:102970000007013900F14040C3F860724F1CF6D1E6 +:10298000203A12F1200FEED1BFF34F8F5A6942F473 +:1029900080325A61BFF34F8FBFF36F8FF0BD00BF1E +:1029A00000ED00E0FEE70000084A094B09498B42B0 +:1029B00004D3094A0021934205D3704752F8040F0B +:1029C00043F8040BF3E743F8041BF4E7D84300088B +:1029D000603500206035002060350020D0F894304C +:1029E000002230B51146D0F890409D684FF0FF307E +:1029F00004EB421301329542C3F80019C3F81019D1 +:102A0000C3F80809C3F8001BC3F8101BC3F8080B70 +:102A1000EED24FF00113C4F81C3830BD00EB810337 +:102A20002DE9F04FD3F80CE04F1C4FEA4118DEF8C7 +:102A300014403F03D4F800C06568D0F89020654585 +:102A40000AD30120D2F8343800FA01F123EA010157 +:102A5000C2F83418BDE8F08FACEB0503BEF8106087 +:102A6000B34228BF334602EB0806D6F81869B6B25F +:102A7000B3EB860F13D8A6683A449946A6F1040A28 +:102A80005AF804BFB9F1040FC2F800B002D9A9F195 +:102A90000409F5E71E442B44A6606360CCE70020E0 +:102AA000BDE8F08F890141F02001016103699B06B7 +:102AB000FCD4122000F03ABF10B50A4C2046FEF7B5 +:102AC000B9FF094BC4F89030084BC4F89430084C57 +:102AD0002046FEF7AFFF074BC4F89030064BC4F812 +:102AE000943010BD14320020000008402442000839 +:102AF000B032002000000440304200080378012B6F +:102B000070B505465DD1494BD0F89040984259D1F7 +:102B1000474B0E216520D3F8D82042F00062C3F85D +:102B2000D820D3F8002142F00062C3F80021D3F886 +:102B30000021D3F8802042F00062C3F88020D3F84F +:102B4000802022F00062C3F88020D3F88030FEF7A6 +:102B5000EBFB384BE360384BC4F800380023D5F862 +:102B60009060C4F8003EC02323604FF40413A363B5 +:102B70003369002BFCDA01230C20336100F0D6FE10 +:102B80003369DB07FCD4122000F0D0FE3369002B40 +:102B9000FCDA00262846A660FFF720FF6B68C4F821 +:102BA0001068DB68C4F81468C4F81C68002B3AD1BC +:102BB000224BA3614FF0FF336361A36843F001032D +:102BC000A36070BD1E4B9842C8D1194B0E214D20F9 +:102BD000D3F8D82042F00072C3F8D820D3F80021EF +:102BE00042F00072C3F80021D3F80021D3F880200E +:102BF00042F00072C3F88020D3F8802022F00072E7 +:102C0000C3F88020D3F88020D3F8D82022F0806247 +:102C1000C3F8D820D3F8002122F08062C3F8002145 +:102C2000D3F8003193E7074BC3E700BF143200200D +:102C3000004402584014004003002002003C30C011 +:102C4000B0320020083C30C0F8B5D0F890400546BE +:102C500000214FF000662046FFF724FFD5F89410BE +:102C600000234FF001128F684FF0FF30C4F8343862 +:102C7000C4F81C2804EB431201339F42C2F80069D8 +:102C8000C2F8006BC2F80809C2F8080BF2D20B6850 +:102C9000D5F89020C5F89830636210231361166947 +:102CA00016F01006FBD1122000F040FED4F80038D8 +:102CB00023F4FE63C4F80038A36943F4402343F0CF +:102CC0001003A3610923C4F81038C4F814380B4B5F +:102CD000EB604FF0C043C4F8103B094BC4F8003B15 +:102CE000C4F81069C4F80039D5F8983003F110021F +:102CF00043F48013C5F89820A362F8BD0042000891 +:102D000040800010D0F8902090F88A10D2F8003857 +:102D100023F4FE6343EA0113C2F800387047000051 +:102D20002DE9F0410EB20D4600EB8608D8F80C10E4 +:102D30000F6807F00303022B53D0032B53D03F4AF5 +:102D40003F4F012B18BF1746D0F890404FEA451E61 +:102D5000002205F1100C04EB0E03C3F8102B8A6956 +:102D6000002A42D04A8A05F158033A435B01E250F7 +:102D70000123D4F81C2803FA0CF31343C4F81C38BD +:102D8000A64400234A69CEF8103905F13F03002A12 +:102D90003BD00A8A04EB8303898B9208012988BF00 +:102DA0004A43D0F89810561841EA02422946C0F822 +:102DB000986020465A60FFF775FED8F80C301B8AE1 +:102DC00043EA85531F4305F148035B01E7500123A4 +:102DD000D4F81C2803FA05F51543C4F81C58BDE8BF +:102DE000F081184FB0E7184FAEE704EB4613D3F865 +:102DF000002B22F40042C3F8002B0123D4F81C2836 +:102E000003FA0CF322EA0303B8E704EB83030F4A47 +:102E100004EB461629465A602046FFF743FED6F8D3 +:102E20000039012223F4004302FA05F5C6F80039FF +:102E3000D4F81C3823EA0505CFE700BF0080001056 +:102E4000008004100080081000800C1000040002B4 +:102E5000D0F894201268C0F89820FFF7BFBD00009A +:102E60005831D0F8903049015B5813F4004004D039 +:102E700013F4001F14BF0120022070474831D0F81E +:102E8000903049015B5813F4004004D013F4001F44 +:102E900014BF01200220704700EB8101CB68196A42 +:102EA0000B6813604B6853607047000000EB8103B0 +:102EB00030B5DD68AA691368D36019B9402B84BFA7 +:102EC000402313606B8A1468D0F890201C4402EBF6 +:102ED0004110013C09B2B4FBF3F46343033323F024 +:102EE000030343EAC44343F0C043C0F8103B2B68DC +:102EF00003F00303012B0ED1D2F8083802EB411086 +:102F000013F4807FD0F8003B14BF43F0805343F0AC +:102F10000053C0F8003B02EB4112D2F8003B43F0F3 +:102F20000443C2F8003B30BD2DE9F041D0F8906079 +:102F300005460C4606EB4113D3F8087B3A07C3F865 +:102F4000087B08D5D6F814381B0704D500EB81039D +:102F5000DB685B689847FA072FD5D6F81438DB078B +:102F60002BD505EB8403D968CCB98B69488A5E6898 +:102F7000B6FBF0F200FB12628AB91868DA68904278 +:102F80000DD2121A83E81400202383F311882146FE +:102F90002846FFF78BFF84F31188BDE8F0810123F9 +:102FA00003FA04F26B8923EA02036B81CB6823B135 +:102FB00021462846BDE8F0411847BDE8F0810000F1 +:102FC00000EB81034A0170B5DD68D0F890306C6980 +:102FD0002668E66056BB1A444FF40020C2F8100978 +:102FE0002A6802F00302012A0AB20ED1D3F80808B7 +:102FF00003EB421410F4807FD4F8000914BF40F0B2 +:10300000805040F00050C4F8000903EB4212D2F89F +:10301000000940F00440C2F800090122D3F8340846 +:1030200002FA01F10143C3F8341870BD19B9402EFA +:1030300084BF4020206020681A442E8A841940F002 +:103040000050013CB4FBF6F440EAC440C6E700007F +:103050002DE9F041D0F8906004460D4606EB41138F +:10306000D3F80879C3F80879FB071CD5D6F81038CF +:10307000DA0718D500EB8103D3F80CE0DEF8143042 +:10308000D3F800C0DA6894451BD2A2EB0C024FF0D3 +:1030900000081A60C3F80480202383F31188FFF727 +:1030A0008FFF88F311883B0618D50123D6F8342802 +:1030B000AB40134212D029462046BDE8F041FFF74D +:1030C000ADBC012303FA01F2038923EA0203038161 +:1030D000DEF80830002BE6D09847E4E7BDE8F08141 +:1030E0002DE9F047D0F8905004466E69AB691E4058 +:1030F000F1046E6103D5BDE8F047FEF715BD002E63 +:1031000012DAD5F8003E9A0705D0D5F8003E23F034 +:103110000303C5F8003ED5F80438204623F0010328 +:10312000C5F80438FEF730FD330502D52046FEF71A +:103130001FFDB7040CD5D5F8083813F0060FEB685F +:1031400023F470530CBF43F4105343F4A053EB60CB +:10315000300704D56368DB680BB120469847F1025D +:1031600000F1A180B2020BD5D4F8908000274FF077 +:103170000109D4F89430F9B29B688B4280F0D28078 +:10318000F3061AD5D4F890100A6AC2F30A1702F0AF +:103190000F0302F4F012B2F5802F00F0EB80B2F5CD +:1031A000402F0AD104EB830301F58051DB68186AD4 +:1031B00000231A469F4240F0D1803003D5F81858BA +:1031C00035D5E90303D500212046FFF7ADFEAA035C +:1031D00003D501212046FFF7A7FE6B0303D502218B +:1031E0002046FFF7A1FE2F0303D503212046FFF75A +:1031F0009BFEE80203D504212046FFF795FEA902B5 +:1032000003D505212046FFF78FFE6A0203D506216C +:103210002046FFF789FE2B0203D507212046FFF742 +:1032200083FEEF0103D508212046FFF77DFE7003E2 +:1032300040F1C780E90703D500212046FFF708FFCA +:10324000AA0703D501212046FFF702FF6B0703D52C +:1032500002212046FFF7FCFE2F0703D5032120465D +:10326000FFF7F6FEEE0603D504212046FFF7F0FE39 +:10327000A80603D505212046FFF7EAFE690603D517 +:1032800006212046FFF7E4FE2A0603D50721204643 +:10329000FFF7DEFEEB0540F1948020460821BDE8F3 +:1032A000F047FFF7D5BED4F890904FF000084FF0EC +:1032B000010AD4F894305FFA88F79B68BB42FFF4A8 +:1032C00051AF09EB4713D3F8002902F44022B2F5BD +:1032D000802F24D1D3F80029002A20DAD3F800293E +:1032E00042F09042C3F80029D3F80029002AFBDB02 +:1032F0003946D4F89000FFF7D5FB22890AFA07F384 +:1033000022EA0303238104EB8703DB689B6813B184 +:1033100039462046984739462046FFF77FFB08F19B +:103320000108C6E708EB4112D2F8003B03F4402342 +:10333000B3F5802F10D1D2F8003B002B0CDA628954 +:1033400009FA01F322EA0303638104EB8103DB68DA +:10335000DB680BB12046984701370AE713F0030FEB +:1033600000D10A68072B03F101039EBF0270120A05 +:1033700001301FE704EB830301F58051DA6890699F +:103380000268D0F808C04068A2EB000E0022104688 +:10339000974208D1DB689B699A683A449A605A68F8 +:1033A00017445F6009E712F0030F00D108689645E3 +:1033B00002F1010282BF8CF80000000A0CF1010C3E +:1033C000E6E7BDE8F087000008B50348FFF788FE90 +:1033D000BDE80840FFF776BA1432002008B503486C +:1033E000FFF77EFEBDE80840FFF76CBAB032002060 +:1033F000D0F8903003EB4111D1F8003B43F40013B7 +:10340000C1F8003B70470000D0F8903003EB411149 +:10341000D1F8003943F40013C1F8003970470000B7 +:10342000D0F8903003EB4111D1F8003B23F40013A6 +:10343000C1F8003B70470000D0F8903003EB411119 +:10344000D1F8003923F40013C1F8003970470000A7 +:1034500030B50433039C0172002104FB0325C361D2 +:10346000049B00600363059B4060C1604261026190 +:103470008561046242628162C162436330BD0000C3 +:103480000022416AC260416101616FF00101826204 +:10349000C262FEF799BE000003694269934203D1FC +:1034A000C2680AB100207047181D7047036919608F +:1034B0000021C2680132C260C2691344826993422A +:1034C000036124BF436A0361FEF772BE38B5044648 +:1034D0000D46E3683BB162690020131D1268A362C8 +:1034E0001344E36238BD237A33B929462046FEF7F8 +:1034F0004FFE0028EDDA38BD6FF00100FBE7000059 +:10350000C368C269013BC360436913448269934243 +:10351000436124BF436A436100238362036B03B1A9 +:103520001847704770B52023044683F31188866AD4 +:103530003EB9FFF7CBFF054618B186F31188284640 +:1035400070BDA36AE26A13F8015B9342A36202D3DF +:103550002046FFF7D5FF002383F31188EFE7000033 +:103560002DE9F84F04460E4690469946202787F3EA +:1035700011880025AA46D4F828B0BBF1000F09D164 +:1035800049462046FFF7A2FF20B18BF31188284659 +:10359000BDE8F88FA16AA8EB050BE36A5B1A9B45AF +:1035A00028BF9B46BBF1400F1BD9334601F14002B7 +:1035B00051F8040B914243F8040BF9D1A36A403649 +:1035C00040354033A362A26AE36A9A4202D320469E +:1035D000FFF796FF8AF311884545D8D287F3118803 +:1035E000C9E730465A46FDF78DFCA36A5E445D4448 +:1035F0005B44A362E7E7000010B5029C043301724C +:10360000C36103FB0421002300608362C362039B48 +:1036100040600363049BC460426102618161046293 +:103620004262436310BD0000026A6FF00101C26094 +:10363000426A4261026100228262C262FEF7C4BD38 +:10364000436902699A4203D1C2680AB100207047F7 +:10365000184650F8043B0B6070470000C368002117 +:10366000C2690133C3604369134482699342436171 +:1036700024BF436A4361FEF79BBD000038B5044692 +:103680000D46E3683BB1236900201A1DA262E2697E +:103690001344E36238BD237A33B929462046FEF746 +:1036A00077FD0028EDDA38BD6FF00100FBE7000080 +:1036B00003691960C268013AC260C2691344826931 +:1036C0009342036124BF436A036100238362036B57 +:1036D00003B118477047000070B5202304460E461A +:1036E00083F31188856A35B91146FFF7C7FF10B11A +:1036F00085F3118870BDA36A1E70A36AE26A013364 +:103700009342A36204D3E16920460439FFF7D0FF56 +:10371000002080F3118870BD2DE9F84F04460D4656 +:1037200091469A464FF0200888F311880026B34648 +:10373000A76A4FB951462046FFF7A0FF20B187F393 +:1037400011883046BDE8F88FA06AA9EB0603E76A46 +:103750003F1A9F4228BF1F46402F1BD905F1400347 +:1037600055F8042B9D4240F8042BF9D1A36A40364A +:103770004033A362A26AE36A9A4204D3E169204615 +:103780000439FFF795FF8BF311884E45D9D288F3A2 +:103790001188CDE729463A46FDF7B4FBA36A3D44BC +:1037A0003E443B44A362E5E7026943699A4203D180 +:1037B000C3681BB9184670470023FBE7836A002BD8 +:1037C000F8D0043B9B1AF5D01360C368013BC3607B +:1037D000C3691A4483699A42026124BF436A036140 +:1037E000002383620123E5E700F050B9034B002278 +:1037F00058631A610222DA60704700BF000C004073 +:103800000022014BDA607047000C0040014B586306 +:10381000704700BF000C0040FEE7000010B5194CD7 +:10382000FEF7BCFBFEF7DEFC802217492046FEF7C0 +:1038300063FC012344F8180C0374144B144AD96830 +:1038400021F4E0610904090C0A431249DA60CA68EC +:1038500042F08072CA60104A1049C2F8B01F116865 +:1038600041F0010111601022DA77202283F8222032 +:10387000002383F3118862B60948BDE81040FEF7C3 +:103880005DBC00BFD42A00203C42000800ED00E0EF +:103890000003FA05F0ED00E0001000E055CEACC5E5 +:1038A000444200082DE9F84F1E4C4FF00008DFF8A5 +:1038B0007890656904F11407D9F82430266AAA685B +:1038C0009E1B96421CD34FF0200AAA68236AD5F8A3 +:1038D0000CB0B61A134423622B68BB425F6063616D +:1038E000C5F80C8001D1FFF78BFF88F31188286998 +:1038F000D8478AF311886569AB689E42E5D2DBE759 +:103900006269BA420CD0916823628E1B9660A868E7 +:1039100002282CBF1818981CBDE8F84FFFF776BF97 +:10392000BDE8F88FAC2A0020000C0040034B59681A :103930005A68521A9042FBD8704700BF001000E04E :103940004B6843608B688360CB68C3600B694361DD :103950004B6903628B6943620B6803607047000028 -:1039600008B52C4B2C48D3F8882040F2FF710A434D +:1039600008B52C4B40F2FF712B48D3F888200A434E :10397000C3F88820D3F8882022F4FF6222F00702DF :10398000C3F88820D3F88820D3F8E0200A43C3F88E :10399000E020D3F808210A43C3F808211F4AD3F8CE @@ -928,21 +928,21 @@ :1039E000FFF7AEFF144802F1C401FFF7A9FF134827 :1039F00002F1E001FFF7A4FF114802F1FC01FFF71B :103A00009FFF104802F58C71FFF79AFFBDE8084050 -:103A100000F016B90044025800000258584200084D +:103A100000F016B900440258000002586442000841 :103A20000004025800080258000C02580010025806 :103A30000014025800180258001C025800200258B6 -:103A4000002402580028025808B500F0C7FAFFF712 -:103A5000E3FEFEF713FFBDE80840FEF7CDBC000013 +:103A4000002402580028025808B500F0CDFAFFF70C +:103A5000E5FEFEF715FFBDE80840FEF7CDBC00000F :103A600070470000084B1A69920710B508D500246A -:103A70001C61202383F31188FFF712FF84F3118860 -:103A8000BDE81040FEF71CBF000C0040124BD3F8FD -:103A9000E82042F00802C3F8E820D3F8102142F0F1 -:103AA0000802C3F810210D4AD3F81031D36B43F04C -:103AB0000803D3630A4B63229A624FF0FF32DA6243 -:103AC00000229A615A63DA605A6001225A61082121 -:103AD0001A603220FDF72CBC004402580010005C34 -:103AE000000C0040F8B5514BD3F880204FF0FF3266 -:103AF000C3F880200024D3F88010C3F88040D3F8A6 +:103A70001C61202383F31188FFF714FF84F311885E +:103A8000BDE81040FEF71EBF000C0040124B08219D +:103A90003220D3F8E82042F00802C3F8E820D3F837 +:103AA000102142F00802C3F810210C4AD3F810315B +:103AB000D36B43F00803D363C722094B9A624FF0DC +:103AC000FF32DA6200229A615A63DA605A60012298 +:103AD0005A611A60FDF728BC004402580010005CCF +:103AE000000C0040F8B5514B0024D3F880204FF073 +:103AF000FF32C3F88020D3F88010C3F88040D3F899 :103B00008010D3F88410C3F88420D3F88410C3F84D :103B10008440D3F88410D96F41F0FF4141F4FF0194 :103B200041F4DF4141F07F01D967D96F21F0FF41B6 @@ -955,134 +955,134 @@ :103B9000D3F89810C3F89840D3F89810D3F88C1045 :103BA000C3F88C20D3F88C10C3F88C40D3F88C1059 :103BB000D3F89C10C3F89C20D3F89C20C3F89C40F9 -:103BC000D3F89C3000F0EAF9194B07229A60194AA1 +:103BC000D3F89C3000F0F0F9194B07229A60194A9B :103BD000DA60194A1A6105225A60184A536A43F496 :103BE00080335362C2F88440BFF34F8FD2F88030E5 -:103BF000C3F3C904C3F34E335B01A50743F6E07674 -:103C000003EA060E284621464EEA00070139C2F8AB -:103C100074724F1C00F14040F6D1203B13F1200F8D +:103BF00043F6E076C3F3C904C3F34E33A5075B0174 +:103C000003EA060E284621464EEA0007013900F174 +:103C10004040C2F874724F1CF6D1203B13F1200FC4 :103C2000EED1BFF34F8FBFF36F8FF8BD0044025842 :103C300090ED00E0000004301B00080300ED00E000 -:103C40005A4B5B4901221A605A4B19609A605A4AD2 +:103C400001225D4B5D491A605D4B19609A605D4AC7 :103C5000DA6000221A614FF440429A619A69920434 -:103C6000FCD51A6842F480721A60544B1A6F12F431 -:103C7000407F1FBF4FF480321A6700221A671A680C -:103C800042F001021A604D4A134611684807FCD5FC +:103C6000FCD51A6842F480721A60574B1A6F12F42E +:103C7000407F04D04FF480321A6700221A671A6816 +:103C800042F001021A60504A134611684807FCD5F9 :103C9000002111611A6912F03802FBD1012119606B -:103CA0004FF0804159605A67454ADA62454A1A61C5 -:103CB0001A6842F480321A60404A13461168890338 +:103CA0004FF0804159605A67484ADA62484A1A61BF +:103CB0001A6842F480321A60434A13461168890335 :103CC000FCD5116841F0800111601A68D205FCD55D -:103CD0003D4A3E499A6200225A631963A1F5C02108 -:103CE0004B39DA6399635A64394A1A64394ADA6299 -:103CF0001A6842F0A8521A60304B1A6802F0285233 -:103D0000B2F1285FF9D109229A610022DA611A62C0 -:103D10004FF00052DA643049304A1A6559659A65A5 -:103D20002F4A212111601A6942F003021A61234BC4 -:103D30001A6902F03802182AFAD1D3F8DC2042F0CE -:103D40000052C3F8DC20D3F8042142F00052C3F83B -:103D50000421D3F80421D3F8DC2042F08042C3F8D8 -:103D6000DC20D3F8042142F08042C3F80421D3F8C8 -:103D70000421D3F8DC2042F00042C3F8DC20D3F861 -:103D8000042142F00042C3F80421D3F80421D3F8FF -:103D9000F42042F00202C3F8F420D3F81C2142F0D0 -:103DA0000202C3F81C21D3F81C317047088100516E -:103DB00000C000F000480258020000010044025810 -:103DC0000000FF01008890083230600063020701A4 -:103DD00047040508FD0BFF010010E0000000011082 -:103DE00000200052084A08B5936811680B4003F0A0 -:103DF0000103936023B1054A13680BB150689847DB -:103E0000BDE80840FEF75CBD80000058C0250020DA -:103E1000084A08B5936811680B4003F002039360E9 -:103E200023B1054A93680BB1D0689847BDE80840B4 -:103E3000FEF746BD80000058C0250020084A08B59E -:103E4000936811680B4003F00403936023B1054AA3 -:103E500013690BB150699847BDE80840FEF730BDC3 -:103E600080000058C0250020084A08B593681168F2 -:103E70000B4003F00803936023B1054A93690BB12B -:103E8000D0699847BDE80840FEF71ABD8000005889 -:103E9000C0250020084A08B5936811680B4003F05C -:103EA0001003936023B1054A136A0BB1506A984717 -:103EB000BDE80840FEF704BD80000058C025002082 -:103EC000174B10B59C681A68144004F478729A6015 -:103ED000A30604D5134A936A0BB1D06A98476006CB -:103EE00004D5104A136B0BB1506B9847210604D5CB -:103EF0000C4A936B0BB1D06B9847E20504D5094A85 -:103F0000136C0BB1506C9847A30504D5054A936C0C -:103F10000BB1D06C9847BDE81040FEF7D1BC00BF94 -:103F200080000058C02500201A4B10B59C681A6804 -:103F3000144004F47C429A60620504D5164A136D5D -:103F40000BB1506D9847230504D5134A936D0BB1FF -:103F5000D06D9847E00404D50F4A136E0BB1506E34 -:103F60009847A10404D50C4A936E0BB1D06E9847C4 -:103F7000620404D5084A136F0BB1506F98472304AD -:103F800004D5054A936F0BB1D06F9847BDE8104038 -:103F9000FEF796BC80000058C0250020062108B519 -:103FA0000846FDF7C5F906210720FDF7C1F90621EE -:103FB0000820FDF7BDF906210920FDF7B9F9062112 -:103FC0000A20FDF7B5F906211720FDF7B1F9062102 -:103FD0002820BDE80840FDF7ABB9000008B5FFF7A1 -:103FE00081FDFDF77DF8FDF749FBFDF721FDFDF7AC -:103FF000F3FBFFF735FDBDE80840FFF7F3BB00001A -:1040000010B501390244904201D1002010BD10F8D2 -:10401000013B11F8014FA342F5D0181B10BD000061 -:10402000034611F8012B03F8012B002AF9D1704740 -:10403000121012131211000001105A00031059003F -:104040000120580003205600EC2A002040260020C2 -:1040500053544D333248373F3F3F0053544D333272 -:10406000483734332F373533000000000096000006 -:104070000000000000000000000000000000000040 -:10408000000000000000000045160008311600087E -:104090006D1600085916000865160008511600082C -:1040A0003D160008291600087916000800000000D7 -:1040B000511700083D170008791700086517000818 -:1040C000711700085D170008491700083517000828 -:1040D000D5170008000000000100000000000000EB -:1040E00002000000000000007D190008E919000826 -:1040F00040004000842F0020942F00200200000088 -:104100000000000003000000000000002D1A00085D -:104110000000000010000000A42F0020000000009C -:104120000100000000000000143200200101020024 -:104130004865782F50726F6669434E43004375623D -:10414000654F72616E67652D424C0025534552499B -:10415000414C25009923000801230008E9180008B4 -:104160007D230008430000006C4100080902430061 -:10417000020100C03209040000010202010005240E -:104180000010010524010001042402020524060098 -:1041900001070582030800FF09040100020A00006C -:1041A00000070501024000000705810240000000F1 -:1041B00012000000B8410008120110010200004086 -:1041C000AE2D1610000201020301000004030904D1 -:1041D00025424F4152442500437562654F72616E1E -:1041E0006765003031323334353637383941424330 -:1041F00044454600000000009D1B00087D1E00088D -:10420000291F0008400040004C3300204C330020A0 -:10421000010000005C33002080000000400100002D -:104220000800000000010000000400000800000079 -:104230006D61696E00000000504200086833002084 -:104240006035002001000000153800080000000063 -:1042500069646C65000000000000802A0000000016 -:10426000AAAAAAAA00000000FFFF000000000000A8 -:1042700000A00A000001000000000000AAAAAAAAEB -:1042800000000000FFFF0000000000000000000030 -:104290000000000000000000AAAAAAAA0000000076 -:1042A000FFFF000000000000000000000000000010 -:1042B00000000000AAAAAAAA00000000FFFF000058 -:1042C000000000000000000000800200000000006C -:1042D000AAAAAAAA00400100FFFF00000000007087 -:1042E000070000000000000000000000AAAAAAAA1F -:1042F00000000000FFFF00000000000000000000C0 -:104300000000000000000000AAAAAAAA0000000005 -:10431000FFFF00000000000000000000000000009F -:1043200000000000AAAAAAAA00000000FFFF0000E7 -:10433000000000000000000000000000000000007D -:10434000AAAAAAAA00000000FFFF000000000000C7 -:10435000000000000000000000000000AAAAAAAAB5 -:1043600000000000FFFF000000000000000000004F -:104370000000000000000000AAAAAAAA0000000095 -:10438000FFFF00000000000000000000000000002F -:10439000FF00000000000000504000083F00000047 -:1043A000500400005B4000083F0000000096000041 -:1043B0000000080004000000CC41000800000000DC -:1043C00000000000000000000000000000000000ED -:0443D00000000000E9 +:103CD000404A41499A6200225A631963A1F5C02102 +:103CE000DA634B3999635A643C4A1A643C4ADA6293 +:103CF0001A6842F0A8521A60334B1A6802F0285230 +:103D0000B2F1285FF9D1482222219A614FF48862EA +:103D1000DA6140221A624FF00052DA64314A1A65C1 +:103D2000314A5A6502F1726202F571429A652F4A70 +:103D300011601A6942F003021A61234B1A6902F0FA +:103D40003802182AFAD1D3F8DC2042F00052C3F826 +:103D5000DC20D3F8042142F00052C3F80421D3F848 +:103D60000421D3F8DC2042F08042C3F8DC20D3F8F1 +:103D7000042142F08042C3F80421D3F80421D3F88F +:103D8000DC2042F00042C3F8DC20D3F8042142F0EA +:103D90000042C3F80421D3F80421D3F8F42042F000 +:103DA0000202C3F8F420D3F81C2142F00202C3F847 +:103DB0001C21D3F81C3170470881005100C000F06D +:103DC0000048025802000001004402580000FF01B0 +:103DD000008890083230600063020701470405083C +:103DE000FD0BFF01000001100010E0000020005258 +:103DF000084A08B5936811680B4003F0010393600B +:103E000023B1054A13680BB150689847BDE80840D4 +:103E1000FEF758BD80000058C0250020084A08B5AC +:103E2000936811680B4003F00203936023B1054AC5 +:103E300093680BB1D0689847BDE80840FEF742BDD3 +:103E400080000058C0250020084A08B59368116812 +:103E50000B4003F00403936023B1054A13690BB1CF +:103E600050699847BDE80840FEF72CBD8000005817 +:103E7000C0250020084A08B5936811680B4003F07C +:103E80000803936023B1054A93690BB1D069984741 +:103E9000BDE80840FEF716BD80000058C025002090 +:103EA000084A08B5936811680B4003F0100393604B +:103EB00023B1054A136A0BB1506A9847BDE8084020 +:103EC000FEF700BD80000058C0250020174B10B53C +:103ED0009C681A68144004F478729A60A30604D5AA +:103EE000134A936A0BB1D06A9847600604D5104A0A +:103EF000136B0BB1506B9847210604D50C4A936B9A +:103F00000BB1D06B9847E20504D5094A136C0BB18D +:103F1000506C9847A30504D5054A936C0BB1D06C3F +:103F20009847BDE81040FEF7CDBC00BF80000058A8 +:103F3000C02500201A4B10B59C681A68144004F480 +:103F40007C429A60620504D5164A136D0BB1506D20 +:103F50009847230504D5134A936D0BB1D06D98474C +:103F6000E00404D50F4A136E0BB1506E9847A104BC +:103F700004D50C4A936E0BB1D06E9847620404D5F9 +:103F8000084A136F0BB1506F9847230404D5054AB4 +:103F9000936F0BB1D06F9847BDE81040FEF792BC0D +:103FA00080000058C0250020062108B50846FDF70E +:103FB000BBF906210720FDF7B7F906210820FDF718 +:103FC000B3F906210920FDF7AFF906210A20FDF714 +:103FD000ABF906211720FDF7A7F906212820BDE837 +:103FE0000840FDF7A1B9000008B5FFF77BFDFDF71C +:103FF00071F8FDF743FBFDF71BFDFDF7EDFBFFF748 +:104000002FFDBDE80840FFF7EFBB000010B50139F8 +:104010000244904201D1002010BD10F8013B11F87C +:10402000014FA342F5D0181B10BD0000034611F844 +:10403000012B03F8012B002AF9D17047121012133B +:104040001211000001105A000310590001205800FD +:1040500003205600EC2A00204026002053544D3304 +:104060003248373F3F3F0053544D333248373433A3 +:104070002F373533000000000096000000000000DC +:104080000000000000000000000000000000000030 +:104090000000000045160008311600086D160008E3 +:1040A0005916000865160008511600083D1600084C +:1040B00029160008791600080000000051170008B2 +:1040C0003D170008791700086517000871170008E8 +:1040D0005D1700084917000835170008D5170008B4 +:1040E00000000000010000000000000002000000CD +:1040F000000000007D190008E91900084000400098 +:10410000842F0020942F00200200000000000000F7 +:1041100003000000000000002D1A0008000000004D +:1041200010000000A42F002000000000010000008B +:104130000000000014320020010102004865782FC1 +:1041400050726F6669434E4300437562654F7261FA +:104150006E67652D424C002553455249414C250060 +:104160009923000801230008E91800087D230008AE +:10417000430000007841000809024300020100C02A +:1041800032090400000102020100052400100105AB +:10419000240100010424020205240600010705820F +:1041A000030800FF09040100020A000000070501DE +:1041B00002400000070581024000000012000000DC +:1041C000C44100081201100102000040AE2D16107B +:1041D00000020102030100000403090425424F41CB +:1041E00052442500437562654F72616E6765003009 +:1041F000313233343536373839414243444546004D +:10420000000000009D1B00087D1E0008291F0008FB +:10421000400040004C3300204C33002001000000DF +:104220005C33002080000000400100000800000016 +:104230000001000000040000080000006D61696ECC +:10424000000000005C420008683300206035002058 +:1042500001000000193800080000000069646C6566 +:10426000000000000000802A00000000AAAAAAAAFC +:1042700000000000FFFF00000000000000A00A0096 +:104280000001000000000000AAAAAAAA0000000085 +:10429000FFFF0000000000000000000014000054B8 +:1042A00000000000AAAAAAAA14000054FFFF000000 +:1042B00000000000000000000040100000000000AE +:1042C000AAAA8AAA00401000FFFF00000000000018 +:1042D000000000000081020000000000AAAAAAAAB3 +:1042E00000410100FFFF0000000000700700000017 +:1042F0000000000000000000AAAAAAAA0000000016 +:10430000FFFF0000000000000000000000000000AF +:1043100000000000AAAAAAAA00000000FFFF0000F7 +:10432000000000000000000000000000000000008D +:10433000AAAAAAAA00000000FFFF000000000000D7 +:10434000000000000000000000000000AAAAAAAAC5 +:1043500000000000FFFF000000000000000000005F +:104360000000000000000000AAAAAAAA00000000A5 +:10437000FFFF00000000000000000000000000003F +:1043800000000000AAAAAAAA00000000FFFF000087 +:104390000000000000000000FF000000000000001E +:1043A0005C4000083F000000500400006740000827 +:1043B0003F0000000096000000000800040000001C +:1043C000D8410008000000000000000000000000CC +:0C43D000000000000000000000000000E1 :00000001FF diff --git a/Tools/bootloaders/MttrCubeOrange_bl.bin b/Tools/bootloaders/MttrCubeOrange_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..022f275dca1a4f46a10da7f3b4e88b3c4a07d299 GIT binary patch literal 17372 zcmd6Odwf*Y_3u89$xI%QArl~(1UNGjG!WE*Kn;R2nF%M4LBqqgF=#!Lh&dA<1ZrFS z)&7_ODi41@qoFn?TG6NlA3)GpqsF1czH5IoV0t066<-}pw4Q;4IeE>w-+d-Qw7vKK zZvVMA`RudTeyzRt+H0@9_S$O*PlTsgV!FaiObZe2pNMZl+>ZQ9!*lsxOA~TC;0zWT>r1zv1f=v)Ocj`YfH-l=S@3{@J+_|h6|=Oe>_JRljJ%_$R7}HxUhIr zA}4sh^5Nk5jSth3qvsTq?3}1OSyHJG^1PRHFJo}QAwcJ{f<85_c7hHoQyHVwHc9srDh_XVRwrbi}@>nJHO+pCvBgsP`#DpNwbc+Wt@=6fO5TqqU*oSq# zG+gniQhCMa=H0(g(?TJH?$6A-yU!{Q6UX-R({|>I`$~zxC~wCZ}9 z@?DP1bu`R&Y-o6{;gg2Bn>K8EZqp~5=5F4wxqb5|n~5Th3msD(lWA5N8|Fn;SvX=4 zLtSR?6YlH~Q}~3t_}tFL89{?c@|d|qV3qU3Q#y$9no5+1#))#@m>?2m<1kTPRx$Iu z&m+7z5TWy6i1DzglPI5#?u!asmAk6g)NSw@J9BojHfI0JD(@sp=@@tT7L^}e?jok7 z@<-G>XJH3%nCzzdM!-bb^cEvDl#-wfd{=y`RytN0#GT?yaW6{uym_VgzItC1xvD6H z^u9NuB;61e?3%4iysU;O1>?VqnheDvKd_s0yYqwBinos3Kl(EH*+8mszIbH`QO=D~ zJo`(uBW)$Oj_etIGiplTq2?X#4QsL2HIg3=o6cNTpER&N>9G5^AuV=!|9S)gU=8$Ru)dH%O zOx~O=gql*=YvVUxmqgFC^li-cOyTL$AEueT4;BR`rRSq5~UZ?U`F^iZm*1mC% zI~HEEYOU8Ux4K>DS^}%RZ88@nwcHRXY;^~ehXdd*pP75q&ybgiyiDX}B2Ph{g1ju`Wg#yMc>!~=LVP`lDQvq0o+#UN zN!cXq-2B=C?-k{#(kwYop4_AJy*=sruM)}46GVP7QJxv$ zZK+ME`-$QoS+HO*{7Hmd@$(Q_&>5mV8RL)>`9wL?$Ow0?BFe52;7eu&0VBG4^wyDG zBdZ}T{&U1AR&}fvlcP*BQGPN)@}uDe;sKFdUhDlygmGLavVsFGaz{_ACg)GxNynXN zwPA#D4utt{3`WRhY})~GfjGP2YH_XiI}%Z@9i84m7Gwp<kqL4+eZ06HnIrReP;M@l%yOz_nk(o!Wmpjbz{;%3Wt7#W;Z#vuJMhbz*cguvhkZM zr}QN#xoenj;@e2U(Q_q@eB1Jh7jI;id=dE#X4^ELm~BzxoGYiD{8d!o%`aZ2aHO#O z#+6wm`N11SJH{Oxv5T7R$}*ySI8xdFLP|lo6Ow56IW6|sIImO7iZSd?GKj4aO2ZA~ zB!9)=)I(bA`#O|-2sBJtC(7m=*}bfs5erS}ZqrpxHPkS|}CHP=BFufiT! zjo<>j7jf2p;<#;sOO_6k{H=p;AEaYV*GKsJ!PFL_{Bk(!MUPrGg|}si@1n0STL^lK z=kyjA#^~&x(pwzVTa--sM4$JkddZ^)AqVw**OXIw{$KR`2M(ql$i({X8{Q@+=CS-` zqFg?_MoiuRScI-@r%G2=yRhjXRyKX>;9Un(222wxyW+y_dhb8iaY+Y3x0GWgp_MBJ zKRD`=9n@lnb?DGRa~o5b7Bbn*2MFfhspmd> zkje!!T1JPp*nf;&jU68!ar}*P;rxS?3ok!-DLq8INswVhTyYSJ=RDLuL z^KG_e83ijYoP3#iX07T_Nbp@FF%2PXFcDJ+;>j?K^rtCECqtJ<{6mBTG>tmHn2499 z5>sTN-B!T+9$?57pPnzp?)VNMz~7N zBaD5a$jK*EVPAn5DrNGG;S}$as*!A0NfS#Y+k?zvcEJbX%E6HaMyY|s(46NYBuI6l zw@7^;wkDhUeAm9vVfAAWBFYa>ONcKVifyZMd*vxqxBi@ z(JHDtk+ab`j5mw+6eMPHv%{-&I#%V#m+$O3pPIBm&Pm%lY!cpf=ZAi_>uq;Zn6anL zHH@+)8)TYae2(GU-MOLSa~xu8$gQWd5Yx0N_$_8L75^9=XXr5UH|%8d)%RhkI57bE+k`y1`{ty0gU52ptoTwKjXv7qfon z9(U`JX|z9Pk2{_A$F;hr(EbpohB=3^f*sh-o!o-?I8>Y#7b2_!XM(OLQd}kA7nG67 zKpf`IW;Yl5!_Dv9$P^AopkEPZXUXi$VJ1Bl=TP%7SP?#!l zA-cjuseQAk`?L8(SX@j@E_XVSXnYwFp4Isx)oT!~TT&9-3;jJU1n#$G*|S6~_N-=* z7>p!=X9e&~@-oFo+s7lgk#x2l{^ERcqimParbheXykR@%ZM~zlKJnjHk6KhG`bxbU z^m_ay^;+xon!$gpTQq^Q`X6vQJ5x%G*FWM;4NX&-WyyI}E@pWw#i{7*GvO3@LAzWDa0So_X&?6{P3f&kN}a%d?#{xyTHQ>z@J{Z{MEOTaeD9IF zE&kMw)&3S}v1%ow-1R2K`r<>Y#mCg!%-P_Sn@9E_=QICXk-(As`*-SaFmk!#GMdrj zChaQee?$`W*aDhZI?bynmtH=?M>7f8OB|Th=CpF6oK^W~5prlc*_(_U-*B=w&9+wf zXoJb?xSdLHGy40^>y)-HA$$(o(o6Y}L0ALw!H{9Dm&`K-vqkPcrl9e5XXmuA-P_`x z8n)@T5w{X>Puxdr30S|AEKHHPyWhEs8(7P|GJ5WOg*=^i2OWyhz$r$~)4!7YNZNzd zc5$`R@8vZHkHT>6l6&y6?^4Ji;S4Es)EIg*6tmqBIuZ@s%7+5#ZBA$RR>w$W1>^<^ zZh@SjW7c*3sN^Ba95$J8C38bQ&u@~S;p8OiJMv28?h zNjs!pNR7T?AM4|4%-yEWZGMlx8T__Q-qy8EW)^Les&n1G>;|`=^Memh^vE6`u@U8k zI1xOa&vmrR&-j^T?b5p3cHi_Zc3{j4ek8a1J_6SYVhbcU zt(h-2bT8DU<9Bhd`LOSPQoC|DA({`%eOZAydy*Lw``((S{ zjr!(JO3#10NY8D)+%1#T+^$oTiwmMzr>6P8Isg9nm-BxQTKNCn{8`x}PxCMm*O5i# zBFS`WF;9>Xx^F0aE#M-=T@!f}eg!ZsOHSl1q%b#8uQrjlh}OFWFg=YSE4z6w2dUQ)@t(SOu~nY7g`YP)Y`c%0ml4jsmvLn5+T*gg z)56RFKDr8eSd)f&C9KG_+3po&qVx~5ht1uY(8DZ=`G6LTG6nD|#Gg#$QTTnpwCsbo zb((<|jB*+~NFXDA?wwgzWPx6~avo3G>s# zrV4kR(Y~#YKa=G3)EOPy>xiSLj@lMIb=&J;w*-_6y$x%%`07q8q&wvuYnZOn%u9G@ zT9`yv8S-&IyG*Osh#LnOjE8U}VwLe29^M^t?yP0Jc zR}@?mVEZG4SQZwcC!6cf6TM(Wc@}x?z1+Yy?zG(IzeQfz!P}%PEhfhkyNOXs#|6ky z>?vK=6?M~fWEA)7^vrXzB)Xd68tC4I?R(j7_X*!fm}~SjHk1}YMkeM$=8|X{M{5^L z9+h9;>>dr%8MsyK=msjyaUa3iKn5B)gSgs1Rm>Foq^u6JonZaekL>eL!rvUBv+X|H z;9`^|U4(GE^fA~th2hZaE*g6pNz}}tpB&l`qjaI3@+xf71C4y?uK#d-EMMz+*1xjR zf!*+oR4XZOF-q?xb&L~rZu1+yQs??NVClo0(=cZzWA5Y{z;}*)>P}}s-HouvN#~uQ z!f1Gh+Tf&f{JvT%=g1DM9I;UiD65q6EW5=c2h@iIgFQ!P8&W~@gnaeLO~_5;87A_Y zfT;nrw7}vW0L)`8DdtVXwQ`$W`{rIXuzI>8B~1_SRU4fKWvgLjKR4HPjxBuBO_ZsP z>rb**5arK-6(m5S;sRQo83jh_PV{p0q1iYNdeV=1LwvA6!&L=WII|4^vou<_Kh_gDd()4(0CiV zJBJ##5~U;1Ipo?}9_oYz?M;k%o0BQ{dH7Y(k=|vVMSOeR^L2l#>xsC|F||*+XP@jG zI=XS$@y?-r8{1JY;CuzpRK2Aj?f~r>#imo)(!uEC=fG9OQCrtu_fg%xNav7wu9gr9Z8I4>tMqnIv#radJTE^3xepA z_o_Rb*UOX!d)4h`)D-rYQX5tEA&*>J$I0z=&qf?u_yTh{!S!_RhvHO^sFgX}4t0-| zBipdnl&Z8JQt(m;xlSIVrPL<{&xTli{QDwTdlMrfjwjLo4znOmQv&IXlFm#GG0N>K zlb;k~sb%QUmEL_AeO=@V?{kQ2BaBk6exc8U6l@(#J48oqLAw=$-#=tc5=6F_QSwGN zqTck;J1^E#4}Mv%=1|T=J#}O~>U}y=70JA~t_9FS=}lFOeKVfW!*1!AezEk+RTtx2 zB=utcm#tRCKY~tu7U#$rgpU!5Iw^ah*mI=yQmfQZ z`V#Ko#Ia50?t$e;eq4UUJ$k%a<|MadmZ~PoP0*R>4&?6R3Jf8>U`nW6K89zU^L z^*fKpr^QZVU!IFJolPTFiIvw$u%(f&;Xe6w+y-y9-*iuwOzT^vEFaa?;<0zS=(xPO z&Q62);Ng^2=8(hB>`$&B$_bU~;2&!|-ZL23J&nT-f0f^ea}PR-rbcMHcjr(ZNQ14a z*jM0hlv^~4;xsHzX@`%#l06db9z$K zd~>G>?`VSGD&HvCCC2XXS?_@zUV~-BPo;1?RROw0%L_o&0TN|Wm&|dnisHkPBkqc_!<{9lzzY^bW}=TE%sN9KtsXZYeM2t zU7fC9j=##6j@z`Pk2$eATI@V@G*c%=q^}me-+yPKovFLLBgyN=%(A3v$s&0q9;KB* zdW%ZTkHdVELROiTR!dppO<2vrw-fpm)rbXohns|px;fb)-7Kv{=_m2Qh{4N6Gudii zs}Fb<_4&XHxXC2wsCIHbcAnLnBp#EBf~@W4`Yf+ioFlGPGjIK|J0)D@Yw_jQ7^Ia_ zqh!j4Edl56={K_KUzGE#Y1!~U&s{Oibz@)PdClXu8Vr0+_zb&k7R zdR00gC+8fHMt!*Pq!E|CPOn;5ImC5p=A1^iIaCb3N&zpfky_o*$(Ucjp4BWj%BdyI z5?+734W%hE5nA0fzID=XBrZ(z80G0Vn&q7`S0dCmOU8<|^%>S?cjVOLR=spyORzaN z3uD^*2JMgbOLaJE!=m&`P!wx4FDb+!F!Pei@H&JVhO&lIZhmW!FCzoTbY1!_*w7jf z@}U1UbhaK&5>3!kn3w0_X8B|Ac{~;$KYGNIyPiC7Hj6kKI0w6!SDEF+kuCNeVHY>K znUhxN(ET?vg~-q4Rdxa0a~Jn(nHD=SLK55n`|M{rAM>JN-VDe^Mwv04n=xZnf?K9m zP|f!CQ9+ziK{aUKXc}7o+eB+~ccPXNdE&@mB$48fx@F|^$Y+qbX3T@)r~58#)qF9n zoR6A_7HifF(ciIr)J&4gwb(L(^} zUOaZ+_^*yYvslb+N$twQy?qf*i+F53Zl34E*qzu9)UIX_(~x`n_=56Z9ibB9ea+Ot zedEHBd9ZP6v6D!dk*d9N%E|ZDrT{`yUgi7h-hBv%uiPSbUDiO~*6BHvuxoX8&%N@> zu+d%&?Jyq88*k`3trDkkNy_39HD&o}_z;w+Nz32FD`B3>F8@o!WG~lirjNIDJ(D}t zYf+gw?4so4bt`{+3#;t-bV9i40}m1V-Z@Ty@RP+Y3iH?9OvP2LHpo(`((G`V*AjV_GRd$ zSZGcUV(OQWgnrx#qt~D%j9y~up2V4+-x?%C0m;Qve#c%IB#rwK!9trj!*e-h{&R=aDdk^;u+{$3@($MQdqI|Auv4{10n%Skrjs}ma=7n19TiUZx z6PKf7II5;Cgh$IliX{P?7p^yszIO_DGDum_i1L-IpXHL^`SFN&I;kSO5`G_t4{I@( zc3{B3c}nIK@EGlSE#Z@q6y4&PQz4W!y9KXM(GqMGx#$=-r}BZ|qmX=67~Kqw&d3nW zWuG4~Oy#6ym;=i#lM3easl=7382FJeJT2xlyKhiA^Puispv6Yxw3T3=hx@iuTqaYk zcA3N|>&Ao*Etab#{6d6p2uogxXj(eSw2`%DjNgnn4KZFX*Xrljmi&%&;Fu5M3^YV@ zH|`MNdP<*>w=rX#H`o$>X_EK&5p!n~B)+-3B$pgnrwRm~O6g~g3`SPFNL9Mm*_pdB zk2k!RyD_&ecVo#QDaox%T}9hEf$VFTYU-p?rqg9y#l|gLXjOXCH+aw z^1pWEm4OG+EhnFch5K>wdH5kzt9-C4%BLSw$zk@?fheCm6q#L8Q1U$P=YPNsr?_@8 z#fred{_1Z_8hbB8Aj&mC*r@Ry5s!6g$=-L=CZ`GCy-t&!cStkpc}aR6>~&O@!jzxq zCZ@wW%)6X`xh+gV12orL!sT8{p%(W|;ZpBZ+XnbFofO;(sp&y{LM4!)6ejR-q9HI* z7C>1*u?A+u zLjP$NIiEvRi3ikWNo zB|AVTV9qQ`^$tMiJnBJu8RZMI43Ho3(q7=?qGlE{&jS2Hdku6^@PI2o%#@Rx)ZOOe z6Zk#-j0NK=qGuv~Ynggvibw_?Fr8G>%;~aG;W)NnU5GzNN%GmiH_0d6Giyal7oEqcC$I4b;qRLx5b z(G?t-zburpo5$<*u04;Mn0Y&c6`qjVV*XZEaX;&xCmvN>BtfhOcYH67(KvHJ=vPQ#^hJ(-gWsB8s(O-1I1=$dGe80N6!z|dbmOd*2>fWjt8&49%vTJ z3Sg}^ znn-J)q&Q3WPE63Gf@uI%D4p;0Unc)e`qrD)5@=V#G1Z(rUuNL}#>`JSG8MY1$;1t~ zGtHPY_EK^tUateIT?$!^9g>U^I_G4U!n-i%WX66%U2I|@*BMU_qdSTGj|BmZdIHxA*L~o-Lbh;N*x_8u=3yPSF`ixmRo#>f@)5Hmm zJlZGkU72(InSnGGvcqJRpaTaI^q{&SeVJaCl-0{P{-iF>e-ZC98KH#!uM}&sm*1i^ zV$N|ojkw0YLenP&e+#vgejK3`#CS?Unbo{_xBo@|Y*&=O+sE~yq%Pzm94|Dmz4W}9GyZcvt+yB4V^NaQ2V}=!!@9Jf zXVARPGq`WvfaC-p)Iw$_tbI{fjGqo1VN-kG!)=CK4q2EC%e!;%E znK`BY*!h&1tdh>LgG$Dcp#VHQ2LeZiTvw%p>CR+^0&7moS@pzW6`yjulrWw%dey9| zCB2_=TrYw35VVND0GQF?pT+M0Os$Gq?CJPbfH@s*i=Sn=US5ZP96tcqpu-Qx>j5X} z@UD0PV51IikAJ~%y(S(0QM`e3MSmUm6nBtBk0$K}z=?NW0Z#OIA^!KI z$sU#Xe!z(y`{RDVi5@?W&j+07@vrd#gDbi>Ac!W|%@w>7_Pz}YHBsIG{Zc6XZXMYf zYm?t}YlCYJB@dKRxi*g-blEB0^1$b09+@xn(b%mtQE4|XkvDpJsR&#II7jWfQbvsD zsqAw!@&gZI=eEHPPTy!-O6gaNZ5=g58Pl&KrU_}l;lz0bJ(wXq$TCup)>pGDd4$n% z)B*?H{gW%tT%8iJz{`+?Q)FWS7iGAg2HA#;6vjD6m$Y;}vH$%n_O0otOMYg6OeJ=+ z_!GA&Oy6T#p&_+O)$+`eTczYkhK|W3Kem#MGVHeCLn?NDN?Mdj`y1u*2cg|`(p&z{ zc=uV83x1(*(6c&`_wN&VcfLW-YAPkTf#PXlD%}Q&gFoqQqp1hX0Tuu*Pqj}Lya5?5+T=hj(%KWQC8(DIN5dnl%en8Gp7!Y{zgXJtiIVTS~Uk8os=s zr=Ii0W1HWm*4ZiINAj|c8b3T%W@X6jHI|Z(YKpoY|5n&VWkx(!i5KF}`--~J8-ZsT z>5-4Y51~i$OyKkA_&h$`FKW0u60hG0-vxR@c%c3|+{=Ei8N{p(YTu{+3GMYC*29W` zx2^UX_5|gd-U(|SJj8UH2lW_e5+4_Z%O6A=GWP}WVE*AZ;eC)CF4sBj8BOS*{s&aH zs}Db2zkk4x`ceIQYun2FV4L`6)Rmrds!(L2E|&h*0KmH!!VSdGa{z?Y9x9SS^mj=d`{4J0-W2tS@P=fwdbx9_$l*A+x#1$Bptf z;vmxYnw}aC>%`UaZSUx7)u^wPrxy1j!q(IEIVQR5=_(R?Vx``JWtoNl!X@h@uEuL% zs(xPg$XG2uQ}~b6jmO%6^UL*eV7;ufo~ii|tMJwJ`T^`mm#!D(0dT-I|HuKCt{7~5 zy8l4J-{k)KC0*07F2B~y9f_BV_WIckblsRjx@!E15B%_5U#i7IxT8~F4eDc}R#I+y z1U@Es=`zt%h+OuH__O*-_>|C9-iI}#6n5%swy*xcKoS?JUtxU;H=a47>#CenhNz4C zrpgyQ>2~2ev0fKf>&sq$tkJcspPZKB$tdrWeh0f#VDs-JbA`G5n0k25G`SdDGfgtv`+gwUx2tx%VbFb4 z^ICFQ!Ww_eTO{}%?2*f%i|f9C+=xM;{)1+6=9_6azQr)x2L6_x+*t6Q2j_~A2P zJcZxoTvq>r{L`Gr+_@*PLMboEj{06T?eJ?>ONpbV0H?#PQmyZoYFdE7uXXn5dPKhe zWGUSp8~iWIKXrd{{B)$o{|3AuACVn3|C#fcv|ncP7X-7iT5_p%5ppz0_v57fnDgEw zSIcXyP43Z?I-M{^uk3-J*>?Dt^+>6HkI(DpYWDa&HK}-;K^@5D1zy)VZBs$n33aEC z0!?Zs?r1v&`=C~1SB&gr`h*71EANnnSdSw^olkE(0)J%wM;J zhI!$MJ3NYsJ5l>Z`8p!;1-Hul8A`@mT&_`W)cvOL<)FT;nBq z^sY|pPuza-+ogaDdH9{u4!}FmuO1_BhxydTVnr)19@LoP!S{=cm95OFx>Fl%$g?5O zhCJIu9@f&lvA=lD#{M;Hu$I8K)BKC`Da<5%0=iuf?w1oWus5O3UgYgXo*pA_FY;QD z*MdAfMqUf@9zxzj$kSuwJ%qd`koN@go)8ct?+GVSl;Lcz(cUU$SM(uReFl5AlvS~= z9=F}Xbv4J-9WH8_I*u1~{C4X5J+MsmoWG&)IpcbU>;JlC>X>>@!ZNkYf?rN0EK}4P zh5It@{!Mgm65g2u^9kLrjQtkxE#+3}7H_uHD&2zq@w()z9CW!`eXagS`LSNB46D{= ztMqNJbz{b$YbzhBgq6!$hkA7=gLT>}t*)?$)8sPa81%|%KC3@NDPrNlVavvCK2Us< zR9#nA(N|N3nd#UTStXC&Viz~oOJz&|GR7(&H;nbVDvHZn!4cK9*|kp(9kun2FO`p$&*D=VNwSBiOtgvoa zSW&%!jc%@Chc>xeH(XVLe*A9SsH{E*xSGW{v*wRLHo zHklSVB~r^8nNr?h8c#(YVa&vgWrKa$RAK6DmZ!<7F6uGUEIB$1@QQ|~FmA1M|Horh z-2q(NslW84b=ir!&8Qo?Sl9he>++L$FM1$TybJzmUDG69)D7w0%Czo`e_Gc(iMJl( zt)Cn(xmb6m*WCGpY?U)z{NR?&tx`Mupe+^6s2xIW2`O`hIv^(^U4UOT6p;DU zr#{1+Vab?AxvQFR=9>s3R1r@27NPHp)Ngv-jn@}0D!Y2ciWOu6TwHk7)k_Kq{d-LR z{?pG&_!urkxC`MXgbfI55Uxd-hj1?fZMX*hh}RSHyKI*OnKrnoAyc5EK06OrK^E(~l5)fM-iFF(tDe!ZPIO zqGTS3S%8K-VrC3^3}N^@mNn!h5yoiP#^G@`nP&)_f`&!|!@6kHNF$Pg@D6ZgFlLN~ zxDH-1!wjS>hk^23GC$W{S-iGn?j=Jb&V`E#7ccq7)kRB--JX(_A}|p0B!u~oW`nly z$DlM>RY(LH=zMQR96;JjWvya@wX3?q7Cr(4`s;1?+k97ETiznb~MvPSBAFR{Q`x*Qr4JQO&w=3Gg;PP t)LSGz|E#~s;{PAYCP{R&ip%x(PV3cc7Xf|0LFba@=2!|0f{3iaP)R literal 0 HcmV?d00001 From 79b41feecefce9c3a57b48cc3d216cbcb0c19eb5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 6 Apr 2020 15:48:24 +1000 Subject: [PATCH 131/155] HAL_ChibiOS: added MttrCubeBlack+ build --- .../hwdef/MttrCubeBlack+/defaults.parm | 258 ++++++++++++++++++ .../hwdef/MttrCubeBlack+/hwdef.dat | 14 + 2 files changed, 272 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm new file mode 100644 index 0000000000..a0627f27cf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm @@ -0,0 +1,258 @@ +AHRS_EKF_TYPE 2 +AHRS_ORIENTATION 2 +AHRS_TRIM_X 0 +AHRS_TRIM_Y -0.0135 +ANGLE_MAX 2000 +ARMING_CHECK 16318 +ATC_ACCEL_P_MAX 36000 +ATC_ACCEL_R_MAX 36000 +ATC_ACCEL_Y_MAX 10000 +ATC_ANG_LIM_TC 3 +ATC_ANG_PIT_P 6 +ATC_ANG_RLL_P 6 +ATC_ANG_YAW_P 5 +ATC_RAT_PIT_D 0.012 +ATC_RAT_PIT_FLTD 6 +ATC_RAT_PIT_FLTT 6 +ATC_RAT_PIT_IMAX 0.444 +ATC_RAT_PIT_P 0.055 +ATC_RAT_RLL_D 0.012 +ATC_RAT_RLL_FLTD 6 +ATC_RAT_RLL_FLTT 6 +ATC_RAT_RLL_I 0.1 +ATC_RAT_RLL_IMAX 0.444 +ATC_RAT_RLL_P 0.055 +ATC_RAT_YAW_D 0 +ATC_RAT_YAW_FLTE 1.617667 +ATC_RAT_YAW_I 0.088756 +ATC_RAT_YAW_IMAX 0.222 +ATC_RAT_YAW_P 0.4435 +ATC_SLEW_YAW 1500 +ATC_THR_MIX_MAX 0.5 +ATC_THR_MIX_MIN 0.1 +BATT_CAPACITY 13000 +BATT_MONITOR 20 +BATT_VOLT_MULT 22.7 +BRD_SAFETYENABLE 0 +BRD_SAFETY_MASK 0 +BRD_SER1_RTSCTS 2 +BRD_SER2_RTSCTS 2 +CAN_D1_UC_ESC_BM 0 +CAN_D1_UC_SRV_BM 0 +CAN_P1_BITRATE 1000000 +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 2 +CAN_D2_UC_ESC_BM 0 +CAN_D2_UC_SRV_BM 0 +RC7_OPTION 0 +CHUTE_ALT_MIN 0 +CHUTE_DELAY_MS 500 +CHUTE_ENABLED 1 +CHUTE_TYPE 11 +COMPASS_DEV_ID 592905 +COMPASS_LEARN 2 +COMPASS_MOTCT 2 +COMPASS_MOT_X 2.38 +COMPASS_MOT_Y -0.67 +COMPASS_MOT_Z 1.93 +COMPASS_USE 1 +COMPASS_USE2 1 +COMPASS_USE3 0 +DISARM_DELAY 20 +EK2_ALT_M_NSE 3 +EK2_CHECK_SCALE 100 +EK2_ENABLE 1 +EK2_GBIAS_P_NSE 0.0004 +EK2_GPS_CHECK -1 +EK2_IMU_MASK 3 +EK2_MAGB_P_NSE 0.0001 +EK2_MAGE_P_NSE 0.001 +EK2_MAG_CAL 3 +EK2_RNG_USE_HGT -1 +FENCE_ENABLE 0 +FLTMODE1 0 +FLTMODE2 0 +FLTMODE3 0 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 9 +FRAME_CLASS 1 +FRAME_TYPE 1 +FS_GCS_ENABLE 0 +FS_THR_ENABLE 6 +FS_THR_VALUE 0 +GND_EFFECT_COMP 1 +GPS_HDOP_GOOD 175 +GPS_POS1_X 0.182 +GPS_POS1_Y -0.05 +GPS_POS1_Z -0.04 +GPS_SAVE_CFG 2 +GPS_TYPE 2 +INS_ACCEL_FILTER 20 +INS_FAST_SAMPLE 7 +INS_GYRO_FILTER 20 +INS_GYR_CAL 0 +INS_POS1_X -0.077 +INS_POS1_Y 0 +INS_POS1_Z -0.05 +INS_POS2_X -0.077 +INS_POS2_Y 0 +INS_POS2_Z -0.05 +INS_POS3_X -0.077 +INS_POS3_Y 0 +INS_POS3_Z -0.05 +INS_TRIM_OPTION 0 +INS_USE 1 +INS_USE2 1 +INS_USE3 1 +LAND_REPOSITION 0 +LAND_SPEED 50 +LAND_SPEED_HIGH 100 +LOG_DISARMED 0 +LOG_FILE_BUFSIZE 40 +LOG_FILE_DSRMROT 1 +LOG_REPLAY 0 +MIS_RESTART 0 +MOT_BAT_CURR_MAX 60 +MOT_BAT_CURR_TC 2 +MOT_BAT_POW_MAX 2000 +MOT_BAT_VOLT_MAX 50.8 +MOT_BAT_VOLT_MIN 35 +MOT_HOVER_LEARN 0 +MOT_PWM_MAX 1940 +MOT_PWM_MIN 1060 +MOT_SAFE_DISARM 0 +MOT_SPIN_ARM 0.11 +MOT_SPIN_MAX 1 +MOT_SPIN_MIN 0.15 +MOT_THST_EXPO 0.8 +PILOT_THR_BHV 0 +PILOT_TKOFF_ALT 150 +PLND_ACC_P_NSE 2 +PLND_CAM_POS_X 0.165 +PLND_CAM_POS_Y -0.014 +PLND_CAM_POS_Z 0.151 +PLND_ENABLED 1 +PLND_LAND_OFS_X 0 +PLND_LAND_OFS_Y -2.6 +PLND_TYPE 2 +PLND_YAW_ALIGN 18000 +PSC_ACC_XY_FILT 5 +RC1_DZ 30 +RC1_MAX 2000 +RC1_MIN 1002 +RC1_TRIM 1500 +RC2_DZ 30 +RC2_MAX 1999 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_DZ 30 +RC3_MAX 1998 +RC3_MIN 999 +RC3_TRIM 1500 +RC4_DZ 40 +RC4_MAX 1997 +RC4_MIN 1002 +RC4_TRIM 1500 +RCMAP_PITCH 2 +RCMAP_ROLL 1 +RCMAP_THROTTLE 3 +RCMAP_YAW 4 +RNGFND2_ADDR 112 +RNGFND2_MAX_CM 700 +RNGFND2_MIN_CM 20 +RNGFND2_TYPE 0 +RNGFND1_ADDR 102 +RNGFND1_GNDCLEAR 15 +RNGFND1_MAX_CM 12000 +RNGFND1_MIN_CM 0 +RNGFND1_POS_X -0.124 +RNGFND1_POS_Y -0.097 +RNGFND1_POS_Z 0.037 +RNGFND1_SCALING 1 +RNGFND1_STOP_PIN 55 +RNGFND1_TYPE 0 +SERIAL0_BAUD 115 +SERIAL0_PROTOCOL 1 +SERIAL1_BAUD 921 +SERIAL1_PROTOCOL 1 +SERIAL2_BAUD 57 +SERIAL2_PROTOCOL 5 +SERIAL3_BAUD 38 +SERIAL3_PROTOCOL 5 +SERIAL4_BAUD 115 +SERIAL4_PROTOCOL 100 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL -1 +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 34 +SERVO3_FUNCTION 36 +SERVO4_FUNCTION 35 +SYSID_MYGCS 255 +TERRAIN_ENABLE 0 +WPNAV_ACCEL 150 +WPNAV_ACCEL_Z 100 +WPNAV_RADIUS 200 +WPNAV_SPEED 1600 +WPNAV_SPEED_DN 400 +WPNAV_SPEED_UP 400 +COMPASS_ORIENT 35 +MOT_THST_HOVER 0.185 +ATC_RAT_PIT_I 0.1 +FS_EKF_ACTION 4 +COMPASS_PRIMARY 1 +FS_EKF_THRESH 0.8 +COMPASS_DEV_ID2 73475 +COMPASS_MOT2_X 1.87 +COMPASS_MOT2_Y 0.45 +COMPASS_MOT2_Z -1.05 +COMPASS_ORIENT2 36 +COMPASS_TYPEMASK 63423 +EK2_ALT_SOURCE 2 +GPS_AUTO_SWITCH 1 +GPS_POS2_X 0.182 +GPS_POS2_Y 0.05 +GPS_POS2_Z -0.04 +GPS_TYPE2 2 +INS_LOG_BAT_MASK 5 +BATT_AMP_PERVLT 45 +BATT_LOW_VOLT 36 +BATT_FS_LOW_ACT 0 +BATT_LOW_MAH 0 +LOIT_ANG_MAX 20 +PSC_ACCZ_D 0 +PSC_ACCZ_FF 0 +PSC_ACCZ_FLTE 20 +PSC_ACCZ_I 0.5 +PSC_ACCZ_IMAX 800 +PSC_ACCZ_P 0.25 +PSC_ANGLE_MAX 0 +PSC_POSXY_P 1.2 +PSC_POSZ_P 1 +PSC_VELXY_D 0.35 +PSC_VELXY_D_FILT 5 +PSC_VELXY_FILT 5 +PSC_VELXY_I 1.2 +PSC_VELXY_IMAX 1000 +PSC_VELXY_P 1.2 +PSC_VELZ_P 3.5 +BATT_CRT_VOLT 0 +PILOT_SPEED_UP 300 +ATC_INPUT_TC 0.0833 +LOIT_BRK_JERK 3400 +LOIT_ACC_MAX 350 +LOIT_SPEED 750 +BRD_SAFETYOPTION 0 +INS_LOG_BAT_OPT 1 +LOG_BITMASK 65535 +ARM_GPS_HACC 2 +ARM_GPS_VACC 2 +LOG_BACKEND_TYPE 1 +TOFF_ALT_CHANGE 2 +TOFF_BARO_DIP 2 +TOFF_HOV_PCT 80 +TOFF_POS_CHANGE 2 +WP_NAVALT_MAX 3 +ESC_CALIBRATION 9 +ADSB_ENABLE 1 +ADSB_LIST_RADIUS 10000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/hwdef.dat new file mode 100644 index 0000000000..3b946260b7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/hwdef.dat @@ -0,0 +1,14 @@ +# hw definition for Matternet CubeBlack+ build + +include ../CubeBlack+/hwdef.dat + +define MODE_SMARTRTL_ENABLED DISABLED +define SPRAYER_ENABLED DISABLED +define GRIPPER_ENABLED DISABLED +define WINCH_ENABLED DISABLED + +# increase arming delay +define ARMING_DELAY_SEC 3.0f + +# log for 60s after disarm +define HAL_LOGGER_ARM_PERSIST 60 From 74468c0505507237188e5388712dd1ff3345e9ad Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 6 Apr 2020 15:48:45 +1000 Subject: [PATCH 132/155] Tools: added MttrCubeBlack+ bootloader --- Tools/bootloaders/MttrCubeBlack+_bl.bin | Bin 0 -> 16272 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 Tools/bootloaders/MttrCubeBlack+_bl.bin diff --git a/Tools/bootloaders/MttrCubeBlack+_bl.bin b/Tools/bootloaders/MttrCubeBlack+_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..2667b2d0d64a8e0fc5e67aff47c8e7d80dc44beb GIT binary patch literal 16272 zcmb_@3w%`7wf8=cNhX;S!_4I5G0`BQy%@Bf$)KJI21cYU z_If`i1TCWXHX3R%(MpZBpcM!@)`)Qs?8COVodMGyk84HIjwQ98K;oP{&-dSF5=Gm4 zzkBcROMd(8*V=3Ez1G@muf6sj!V~NJ4AB>468$`c`zGTX5nn+0l_9I>%lRwozM8&o zDbYWN5JMP8D8Avp-*yVu*Z&u7rrH)~5&a5;-v1_!hpzvhk8i54sd#+R{~pK980!?C z|DQ2?p2$R*h;MmiX;tX5epflZY53msnf~VAUm}cNbY3FlcL+CqR(4OaByzd#`;p6= zzfWt9U6N6=YZ7*0Xr-a_W8h7`8EPtQaTQ6trDiZcp5-TJBZGw@1G(p~*hzG+3wVUM}&K~6K zWS&2`Szehk*Zy4aqu{)I?zrcu7D$mMuM|gpiJtI2d zbdS;dq{|XzN}qI@BRXN#rCnuwgqcT2%gQrGrganf6@|!+<3zTMSp_0b8z%CL3Mf$c zNt_q@<8)38NjBP+zD?mrpIt`u zDbA8L6;nAZ5`piY1{T}tmPNnd0UrbHBs*<8uOn-iUQ%Zkp%3;^rQ8jT8WpBlZwfAG? z`;7Lb<1&V=8aJ}5PDqAsMt*UE*o`%rRds{ky@!#TkfXesR%@3`-FAstW*7ZP`H}LA zdT-vg(jLEL?_sS(-a59#?iY={BvJ;vFY-jcZ62`(wLa!~=T+A${58xH5;OKb>{4R3 zTD#XKb+~RgWAk=O+yL=&Lm_vEYspE-mn@CW_Oe!U5HdNI@3q`bY?ckVn=E(cZo1{} zh7GrDYPhpuQ$xTdhu8*RL%=o}TTnvQSbP?g&^Rx!<&|kQ)4e7!PqInYf)>o=DWMfB z)>ui$IR+WdcM?61pdwBAPRC2iS*QLJa-N`^%J371U#ex=C~u7WeBn96dPg0QSG<84cWjZY4b2VMn%+u^+#BK_D#V3S( zVYaYWU@+^qN69rr&fd}K&67xpQ=YaX_b^>AtW{0)Opqd{Jleu^_CQkfk-5SiFO|fF z4z|DmS$ulr-8gs#iY*%9=5Xy7&(T&tn%E(bq7S27=ejw35xMkk%X=RanVX)KGmDt_ z>+DXYYz1FHnkv_aN%I= zqd2+x=TWjS9Hl)4CUoeD$cI`O>)o|jHzTaoiqYIY3cP8zk32N88dx3~Nfp+0)6@?~ z(gv6`QZx`-C>#*TRetXeXpWGp)WkIt>oKO4gUyG?!j*$fhuF@f49y;00_r|9e0YGQ zAG`F;7K_a3oN_}8`mm<-r*rKta;d)MwV}{lM?^CMo&QFyF>^l9FSWJT1#> z_|6yBGS_|@|21ZNX*@aG@|L-avQGbUz{;3JQK)dvM zN(<{_75OJ$8dXz_-cV` zC-N_cxlTjdr*ZRszQC!}t|0Qm!y7dHwiRphtLyY9&|?cB{|?QJvVe<=arD_^qU>5!zeSOiwsFy;{v<2Z?+{D|b#iqm{4J${##vIFJMWJwLodNX}#Vi$uO^_-4Vd|M58GY*?Y3 zRX@AuAUK=3eX#i;rC55u9-LkI*_~SNxf(9Ir#oTC*4duR5qEvbEHqgT_v#G$X3F84nQ5f0kDI?7^f~Aae1Dn)r0=`YJ|# zWYqp=DuoLUQYpOZ;Fa{)tI+kheK21e(;vntzh@rg+SEjB4EvOWk();;MQ<7*vVMf? z{3lI2$RFv1hyG00r~1)6Vf>?o!d-u+T5_q9luz}u3olar@$@j?S+Fd-WaVe4Uu2$H zqu6B@cmfb;7E{>Wmq?=<5HYN=uW*C@;L?>g#N9heI@%z z5pHyo!Y}t_oa~FgqA$Kk7fbWfe&~Le?B~K{Kd)>3(9$dWalD-BwQNiE)+;urU3xd5 z^QH?w6BxlNI9?aAhfj@%(jXXSBk7oF|whT5S`Z|>9C)6T3TJ~8KZ}hfA%_d zqe|MA;wTTN-pC6@k`*;S9V_agsosyv(fZZb%h3;oGs+yNj~yN&+jXabfAzj0eX=j$ zVZ6uIQCr0LU3D(wHPaD9h?PGd3@`BJOK)8^aD^HEZs#SFtKGFY>b#VT_!`6oh_8-u z_JW#>dAd=~ew)-jthc%@G2D}`!syFGq1)}zRa&k9F^AH*h*J^kBa3aGIT;>ig+b_Y z%{e(^nAyB8|M6~4APRH$5VZX}an^n^zS3s6@sIIR+lBZl+xzhb+lTR6Y#+oI&fDpl z9c0ez&2I=gEx}&1FbYeSKmR+(#Lp12y$!oC3TC&f{YXyqC5*#F$HBI{vgkMvXVP&X zo)+Wn`Wm*sl{>u+v$iYf`7`u980YMeHfo^(@2kMc7O@f5TQ?Y5)8W(TV`QC^W%8HH zmpm?X4Db+@v#EIg#G4?u|g@Qs^urI;YYH<7&a2-t=WaRH*ubaf#@OL;JVf~Hio=07V zXqLh(ODkOGWR@qQ&dY==akgGuO%icOueJ5nPl%nbwg?TYe{I&6hDu!GFnIDLXu(Qu zDa*}>T(`LrydZ4NDakD#<4%dld5H5%`Kqtvw-G0F+N!8>>xP6>DxKBogeQ+o>q}aY zb%W#{-k~ObuWlX;-CHUqZO3Gt4!cv1d<|C`qZWC2%8b5(6w_oo-9R}Za{UM?63*%i zie{^c7uCAYw%@zVd3h4YcT=YK`BO3`;V<4@(%j)`g{NS5E{+-l z(2lFjmG)FqG)LBFW<*FqsNj5RRb-WHWuDPuC*!B_VCWtv`1ft~*_3-FUEdEBF{en# z1>bu|%A{wH{3IR}--ur&J5yKkMvQA^2IX}^{6!o+wCKZJm73V5_I|8~9=rc&{(NFh zmTj6W+j4a0f~m3%lV#G;zb>NZmg%+AYhaneF8QaCY2LS#Tgx(Pr%jgJG-A+747G+D zQb6t3ijj1!1nV+F`x$^QhVqKyXN*XLPZVz!O@l|};iWfn_mg6CWSYQ~@WL@=!&+nP zTJK($D^`XRiEEH7v23tx(&9VwHW>=$V+U?h7J1)MZY}I^l}K!KVfAj8H@2{v>91$H zM=xJKuuIRoB6c~IaB?c=zUbuI#r|Dx*~xVtG5Ja!a?1=-^}bbue7##<2zg=#_uY(h zg4jJ2+H8{QrHsgSyK3L5h-KxyvoMy7Se7=H5Y9(*EQqzSTxESVZbbdhu?u3Xa>%9C z(^#utW8EK5t3DDZk%d^}lpgfVLyU}* zy8+`zAB0+)Pr>$0xUyweG zw@P&7@X(1fg!vk7XW%+u&lFNlQm7TN1l)mk7Zckd?daJdF-vxc z4f!r#ZqOCr0v#^q)CtM$qmuai1f;c>+A(_Q^I+I&=Y{Dwac1p$PI|7pOL`{2Eb9{M z^SgXAw%LHOFmgfa@?8iRx~;-q>`h6(NU(P?^e2(;#hLGevk#zku=nb}Bl$;5jhdK< z6z(>psjZ%^L+ej8qsEH!apoVDAxCOJ**j`Hw{0541v@_P6JJyun_S}gDbIcVPj zKBSzr&W4TSqx-X(cpy^V`_*}y!k&%qD0|8*Qr0%Uct)(?ezrI}mV00JLyY}lrwLkz zIlvFp5=LG(0XPrSS#TdKSS2E#9cB+3dvkD(Ifrp1>Bh)?NY|q5#W#{=H2qVgDcpf1 z9O%Z#U6XM4CE=D(xOD6t8AF+*T zCj&cK*h7y~9CU2`V`*Ndo!yfx;fL&7C`~C1j*Rn%gS`@X^298ne{&|$8zif32c$p! zKCXWU+vcmeFKvliv60>PWp|^5+v{WP+}2~to}47l=vd0b+;(0tb+;*N9WV4)XEXEI z0yVKjrF@(Boy{`Cz^5{{Q(3#3_Db_f`|4j{{bMB+@B+0PEGn_vzXK>oQV!r{m`6wd z>=nI9xOFzg!T>v`Cap9zaZ{vC@i;hH4QNPx#?GMT&tv3SO06A5KaRFIZxfPqVI&ovauc zsMQq-@cWLh>t+tn)V1SZmZG04RLZel`dhd}_{o3{+GnskseN?)52jjY>oNLgCq||9 zfjp_U%mnSp$kuV@0F9?Z0;;;1&c&J*d{jx&m^&=@j!F%IY>6xwistQRmYJLbkQonq zF`l-#JiJ;daQ??+9~e!cNm@g>$DNZp1Gh;P-F$&)RufGV$(6*&S@0aIi6fK#(ehr( zLn5DyFm^6TSM~{CYa`cqqS4*R`MDN%OOnU@qz)zXR*An5b-oJU13n`EO2zsOQaukm zVLEG_usU#7oG#=D=5C{nV79}<`vOzx%fobTy&ngi;ODEbKObUchGkn^TI^~eHrD6z z?eH0Hk$)CG}P{9CAxteongJe>QI4 z#+Mjl$#qHResqG`5q@c>QU{MaS5N@HQmWE^NXgHlD0lD}Eu}swc{a*wRBR;7QwRw<|?SmPI z=(tU2w{q~?hb$>pf$d{teq?i;krTsre-5V{`~t4=P~Ifme+;h&+#iP5#dALAYYD7R zD#>bM{Y26ZyRCc1=e1vOy>^0&8$K`pqScy-3$U^GVsB_e*n?0WrV`EzGfIk2zxOdG zf31lA;cF;fswHXeYi)|x*rwE2Pi%BuWNaO-oHNIz?ATwa{A^XD$u&D>8Vt?IjCHcJ`V86{{qkr|k0&+R324ssQc2HLe{_|>Q-waS zn(Q<8D}8=~K3OlZ<%#RX4xA;{!uNn(X6p{>8Izun9(9eLY>+t7B^t$bll6MoL3F)w z_j4t>C|@!yTGB)F`d)Vcw?-nhLEJtyaSrS9QoQZs3}O*ksa}NVhkOP1>969}d2<8$ zt!9apEMmQA_CdFAok;BIq2qFdz4_letP|2}jZu3by@uWgo>Hg{{-Mg_u7~DRhwXuN zfmG~eusc*GPTMulr81Cl<0@ZCphfDyoS;)rCvCBZBJ@1;pvu@6`WV5!HMu)aB-Zzk z2yM&5N0=9AgC5-L+5_($-F<1fF|5b^oHbyPY~osxvDtl=t!ko8g%<`Vd82b8af3GI z9U^OEw-TFcD|T(EYv6v?tz;}@18!ycLKnW}3sY;{O8&y*l3Ot@WNnkgtt7$sILu8FrUGj1g(v(xd*H zlkN1q)!ivx7iMM_8$^@n7J1axMd&FiIX@2bO^I40R$MLK;-fSgd}C@qod&yer;EfO z*OFblRjdH7Kbjbf>%81R4sHiKe898htPiq)lT4D1N|^ImyvM~`n=D?7z!tAja&9k= zumwMGr3iC{^w>JzUSEErPOK1HM13yqOR>-P^q8AokP0msx$LPAEmuqY`6pfMN$QP# zefS0GN!Q@%jncj1wc;FcllZcDK%#P&mUloL_2I;mL7W<&UbfWQg?c4tZi~wpT?M&H zhb-PKcDP_?F>i`ov|VbE44!rox60mNWxCYpBi0UAz4&X9i_tPh-rmzL?UFda=xeM^ zYnrkx?XLKlCoD|y-bj1C*^`9YqVb#dOYJi1Z=>`|QWQKYPKj~|OmRvTZq5Lqs|r?f z3pyfv73n{&om1|HpU;Y*hfNm@cN}J3OcC_Zg*n)NegHY2NbDa!cEp{(o;>)mna~@1 zKXxIuELS*tq|L<-usn0x0=xL)t-Qi6&Rd{nWLVidq+Nr zKM9?CjOt$Cr|S+rqH5fu59kR!7wHCm!}0@0l2)xI9#M5ezuCe=(o?FF>#;RLBDa>~ zL=PJL6*z_wQb7}HpXhPEnn=ta|K$ zjqU5n^gfesQkc1EY4sIv-^MCze(pB9$Fc(~OY>a*r!jMx{@P!}=LeZ+odtbW&IvwzK=B^4o{K$FR+R^5ZD*ROR_TGitdkKE5HI`%>Ek^!JZD$n) z!=}@Q8bhsVo4?0!6IPGUqu7n#Q0%LjQgcbMClO-p(zF@UKdZSvEXAa*SX08TNA8CJA4BT1|Xc zRTDc@Q}t#0Z^aDz;nB;NxY2BKig8~&#+^F?FZ;dJsxtTt0rz02)BxS&!L9jmBO|AKDLO$DJ)R+zi1P+hIO3z;0fCav^p?6UwfSmei^V zk9ygDK~xjhsjwce;;v@Sw8CdwSeq$0EhsVf=NUXq3F%Kwu?GrI+tJRBF}PLj{YR@k zU>|heYxmg$%iMM!UJPwa5h-ug#B`ODe&o_)XPatMtZFYuTKN^c<2UiCcJ7OMVC)gD zSJ-8xp=4Wm;<{ZukjGb!yySW#`Yvdu`4*{+RD0$`oEFh{l2MEFGo_Ra^OcNapB&GvC*5Et?;AHhOFU^jovmzXgZ~) zUZQlY7jfg!DwVe4wOCT~1uGq&lJnG;L-$mpcfDj9Bz|*r;BUqo0K2nJ4&CcfYL^?l z=OmA!U;gZX#L?C`5009#YkHK`%Z*Vm+Z)2bhK z@u$+@5pQ?tP6aF1fSzu=5xX46H*YZh$V%9$c*ivrTALkVVtY#RG-u&;i0a_`T_$G9 z4_qe{l6yiiBIwhQ&O;hOZ}{8EI+-!OrR0}8dLLrwT><=ufzFh%ce3FdfB6lom+KF) z^hWojl5zgF=07PpRw4hSLXPSBQ?AqXJIyysz6!&sKBcS(wifQdZ5Ijog;J(BN4b>UT%T{x|ntDimcQvc3O#gU1$lJ_@vlidc(EQc+N7D=3*7bpjgfuqCdqJFo+Xhlj?D&4|nB6XJYOWhx zjZ<1_fRv1#W$dNC4A5l3L}}n$YLY&MNYgqp|0nQ#Q(x{z=`F=5ox?W=Az$+LqVevzgMTUB?v?K-hR3yhSivI%$xan)~nYHyZ6G-^{>F*_bjKqx}3G zyf&oVJ~-j0Gwp(gbK2dqk?ZoMVb;cSjJiDC+Ybx;m>cEaz-jY_W(ba#e`(be3h++>7IXqep>852fR9;~FE|LI3a|AYEz;CzNLQ%c2cH(Rng z$|0<%Sy9K7m?N_UPjlVHiaC7$bUed>T$bz(=mv}#WPvkUvs*W?j$6;%;QnAW?w&Dk zZY1Nf$^8>g4Mvm?Uj1G%F4YaJDWt?U zNaz|Wp<|$Oo^jcBk>g%NeJeK|dnVv!CQqHWPW%zH!X2&~QoR)L<&2FT(GA%z>U4jI z6VQuF*&WT<((yagL;?J!>lVA4tC{udpi`WD6yLcy5yr}5$0MZbzo>)9 zi21FQ+hmYTq8Dc+3QxUKj_|wE^8u4|O3dwXmh6l;aWl1XcaG$0&i63OUmm?Y=y!9a zcFLFjRq!0V<;Jb3`xtm%B5^2XO45!@kDXNX<+L8B$n8-`L{7vlhj8CT>W?9Znrv`? znOo-F;QTU&W<$xV3UA!hoYLUD4+pAte^Yv8RK7$;vm1B!n5DB)n`_$1Y)k9MIV7on4OIo; z>uz-?bTQ={tEoMPF=8bXdxqerU5%b2%Ny~{i<O??DZIwN@lb20ZHy38j}=8>x`;_YH`_H^!h)$d{Mr75%x z)xllx_Gd-uIaGmlGPgHL5l*8B*YYsDI3Gs~;NkfwPTvbqdOTi5E#8XeO@S8zbDT2= zL$`18!K#l=B>prGEOlyP*Xv|a_Srt@#fPgpQ|ClziptC{5ces3Io&CLfp{YE>G<_J zwr@ujZF`u{z?k&qCOIXuU$PGd>oX$mL1Vppa9@4DxHy&X^Fvb_y1!kuxAGF(@XkwY zM&CQiT3FM+{xP`Euo^sD2Yz2S#$5l~xPEfYanRs+Npp=6Ym_V_B^hTM(Vo%T`_aAy?J13E zYv%fI#Gg#nN7AL#lD!c&$PM5{P$WB@aRlOQDX7O%>aCI50<08O^v9giGyP;bu^ELQ zx-{zY@aG0PaNFA!rYV07QU1p<>sC6@tvHX6zH_u z&o@PvkA;7pZ*(=bG``vB_ETL%Y^$19`551EaYy6vMtTo3kvIz928TOMy#I+Em(siG ziP}6HC+a}1cpPVkj;CeMXN zoKt)4-!1K-JHSNZ9=zKA4PSm1J`#o;%(6>x|8)ydSX5We!6<;ZEu_KgkZgj zY6CLwdEp(U=BKA8PT}Z)Gc)f@ zslW_4S^7H!YGXd?8jf`}IZK__bu~J#eFiP?{zU8jadkH^RaBflNqc)c?hqP;@x(uk zcQvi|eACm_c$){FN`fFUyCCV@Bvd#_OrscHsI{#ETJ>wX|vud$dj7=oSM94Oy zny#M*#u>XuF=udFv%T3hXQYC`^S(4bEhF7+tUfFLMuIiJU5+SHeEE@&VI*g zYgKIUJkv8(<12dX_|%8GqxXLJkesknwYO&6h)$;O(~RVN70M|6=hnWbgxc;1;LbJ` zwzd8Yya@A~o|k@<_qc2JDR3qIdCA_?r(_&9dF+iP(oxs#;!pb76u<8mN=Asm?>5?0 zO3|Xg=}NjL?g+eqQ}~A`&&C@Auema!k4pB&f6IGZ+%K_33nOOp-u&c_`p*%%3X{G~ zN+ZsDi_{>kv9!5HPiyqS7`>8Pd{}A~e=D63;f?Tl1602W@{JVYJEzs;ZED8}3opn;ymPd5G~$f3=&0z^Nz&lO~8UnZA zcPo~rM!YMvG+LV2$+)3uU1LMjEeP7Htu>Rcw$@ngv}`ie7$xUmC}F+4hKX71ps<6XB^J>jb#h~U-p%y1>Ah=?w_$S|+Rni#g<=bB z0XBFyZsEuJX5n_?F=njKT+<O_nqhze1ZCb6(PA1FyFO z?OF8S0UJ4k)h`%{HQ-fU$kni+fxcvOHQc#=Q?L@yTcH1w^u?UaYn`cN&n|dn`SV#D zlDXR2ujbQI7ca>g3dMzr0yx3U1ajGA`jqR4%q=$mwd@ zk&7ai)NGMAK;KEaSgz>jepiF95%4o>OwDNBytmSh9C}4Airjgg@5`()Z9?6qy_G*k z4!t55MXnJ!eT``|>NcYta_AMgD00bOcYZ#%lmdNNj~(Q@$tkmbv%(dp(e(0;?QH2pLrej znSi&xC3s0)LKe_>yxGQVQ+5_1^=oe|T_UVpxsnjVSWB^qtYR2r1H&0_VN#8Y859%x z-kjE(ctSF82SC%gNY9*17a(n&Ow)S?`kr#?{bUkS=lk54FV^h9y;ZY`bRlmd$qt+&8(2 z`&*57xbF7(Hv3N;o*|pbQU%qse%k8NU&ygmcBR!hXH;NYMJ5 Date: Mon, 13 Apr 2020 16:26:26 +1000 Subject: [PATCH 133/155] HAL_ChibiOS: updated MttrCube parms to better match mate parms --- .../hwdef/MttrCubeBlack+/defaults.parm | 515 +++++++++--------- .../hwdef/MttrCubeBlack/defaults.parm | 515 +++++++++--------- .../hwdef/MttrCubeOrange/defaults.parm | 65 ++- 3 files changed, 546 insertions(+), 549 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm index a0627f27cf..e63269317f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack+/defaults.parm @@ -1,258 +1,257 @@ -AHRS_EKF_TYPE 2 -AHRS_ORIENTATION 2 -AHRS_TRIM_X 0 -AHRS_TRIM_Y -0.0135 -ANGLE_MAX 2000 -ARMING_CHECK 16318 -ATC_ACCEL_P_MAX 36000 -ATC_ACCEL_R_MAX 36000 -ATC_ACCEL_Y_MAX 10000 -ATC_ANG_LIM_TC 3 -ATC_ANG_PIT_P 6 -ATC_ANG_RLL_P 6 -ATC_ANG_YAW_P 5 -ATC_RAT_PIT_D 0.012 -ATC_RAT_PIT_FLTD 6 -ATC_RAT_PIT_FLTT 6 -ATC_RAT_PIT_IMAX 0.444 -ATC_RAT_PIT_P 0.055 -ATC_RAT_RLL_D 0.012 -ATC_RAT_RLL_FLTD 6 -ATC_RAT_RLL_FLTT 6 -ATC_RAT_RLL_I 0.1 -ATC_RAT_RLL_IMAX 0.444 -ATC_RAT_RLL_P 0.055 -ATC_RAT_YAW_D 0 -ATC_RAT_YAW_FLTE 1.617667 -ATC_RAT_YAW_I 0.088756 -ATC_RAT_YAW_IMAX 0.222 -ATC_RAT_YAW_P 0.4435 -ATC_SLEW_YAW 1500 -ATC_THR_MIX_MAX 0.5 -ATC_THR_MIX_MIN 0.1 -BATT_CAPACITY 13000 -BATT_MONITOR 20 -BATT_VOLT_MULT 22.7 -BRD_SAFETYENABLE 0 -BRD_SAFETY_MASK 0 -BRD_SER1_RTSCTS 2 -BRD_SER2_RTSCTS 2 -CAN_D1_UC_ESC_BM 0 -CAN_D1_UC_SRV_BM 0 -CAN_P1_BITRATE 1000000 -CAN_P1_DRIVER 1 -CAN_P2_DRIVER 2 -CAN_D2_UC_ESC_BM 0 -CAN_D2_UC_SRV_BM 0 -RC7_OPTION 0 -CHUTE_ALT_MIN 0 -CHUTE_DELAY_MS 500 -CHUTE_ENABLED 1 -CHUTE_TYPE 11 -COMPASS_DEV_ID 592905 -COMPASS_LEARN 2 -COMPASS_MOTCT 2 -COMPASS_MOT_X 2.38 -COMPASS_MOT_Y -0.67 -COMPASS_MOT_Z 1.93 -COMPASS_USE 1 -COMPASS_USE2 1 -COMPASS_USE3 0 -DISARM_DELAY 20 -EK2_ALT_M_NSE 3 -EK2_CHECK_SCALE 100 -EK2_ENABLE 1 -EK2_GBIAS_P_NSE 0.0004 -EK2_GPS_CHECK -1 -EK2_IMU_MASK 3 -EK2_MAGB_P_NSE 0.0001 -EK2_MAGE_P_NSE 0.001 -EK2_MAG_CAL 3 -EK2_RNG_USE_HGT -1 -FENCE_ENABLE 0 -FLTMODE1 0 -FLTMODE2 0 -FLTMODE3 0 -FLTMODE4 5 -FLTMODE5 2 -FLTMODE6 9 -FRAME_CLASS 1 -FRAME_TYPE 1 -FS_GCS_ENABLE 0 -FS_THR_ENABLE 6 -FS_THR_VALUE 0 -GND_EFFECT_COMP 1 -GPS_HDOP_GOOD 175 -GPS_POS1_X 0.182 -GPS_POS1_Y -0.05 -GPS_POS1_Z -0.04 -GPS_SAVE_CFG 2 -GPS_TYPE 2 -INS_ACCEL_FILTER 20 -INS_FAST_SAMPLE 7 -INS_GYRO_FILTER 20 -INS_GYR_CAL 0 -INS_POS1_X -0.077 -INS_POS1_Y 0 -INS_POS1_Z -0.05 -INS_POS2_X -0.077 -INS_POS2_Y 0 -INS_POS2_Z -0.05 -INS_POS3_X -0.077 -INS_POS3_Y 0 -INS_POS3_Z -0.05 -INS_TRIM_OPTION 0 -INS_USE 1 -INS_USE2 1 -INS_USE3 1 -LAND_REPOSITION 0 -LAND_SPEED 50 -LAND_SPEED_HIGH 100 -LOG_DISARMED 0 -LOG_FILE_BUFSIZE 40 -LOG_FILE_DSRMROT 1 -LOG_REPLAY 0 -MIS_RESTART 0 -MOT_BAT_CURR_MAX 60 -MOT_BAT_CURR_TC 2 -MOT_BAT_POW_MAX 2000 -MOT_BAT_VOLT_MAX 50.8 -MOT_BAT_VOLT_MIN 35 -MOT_HOVER_LEARN 0 -MOT_PWM_MAX 1940 -MOT_PWM_MIN 1060 -MOT_SAFE_DISARM 0 -MOT_SPIN_ARM 0.11 -MOT_SPIN_MAX 1 -MOT_SPIN_MIN 0.15 -MOT_THST_EXPO 0.8 -PILOT_THR_BHV 0 -PILOT_TKOFF_ALT 150 -PLND_ACC_P_NSE 2 -PLND_CAM_POS_X 0.165 -PLND_CAM_POS_Y -0.014 -PLND_CAM_POS_Z 0.151 -PLND_ENABLED 1 -PLND_LAND_OFS_X 0 -PLND_LAND_OFS_Y -2.6 -PLND_TYPE 2 -PLND_YAW_ALIGN 18000 -PSC_ACC_XY_FILT 5 -RC1_DZ 30 -RC1_MAX 2000 -RC1_MIN 1002 -RC1_TRIM 1500 -RC2_DZ 30 -RC2_MAX 1999 -RC2_MIN 1000 -RC2_TRIM 1500 -RC3_DZ 30 -RC3_MAX 1998 -RC3_MIN 999 -RC3_TRIM 1500 -RC4_DZ 40 -RC4_MAX 1997 -RC4_MIN 1002 -RC4_TRIM 1500 -RCMAP_PITCH 2 -RCMAP_ROLL 1 -RCMAP_THROTTLE 3 -RCMAP_YAW 4 -RNGFND2_ADDR 112 -RNGFND2_MAX_CM 700 -RNGFND2_MIN_CM 20 -RNGFND2_TYPE 0 -RNGFND1_ADDR 102 -RNGFND1_GNDCLEAR 15 -RNGFND1_MAX_CM 12000 -RNGFND1_MIN_CM 0 -RNGFND1_POS_X -0.124 -RNGFND1_POS_Y -0.097 -RNGFND1_POS_Z 0.037 -RNGFND1_SCALING 1 -RNGFND1_STOP_PIN 55 -RNGFND1_TYPE 0 -SERIAL0_BAUD 115 -SERIAL0_PROTOCOL 1 -SERIAL1_BAUD 921 -SERIAL1_PROTOCOL 1 -SERIAL2_BAUD 57 -SERIAL2_PROTOCOL 5 -SERIAL3_BAUD 38 -SERIAL3_PROTOCOL 5 -SERIAL4_BAUD 115 -SERIAL4_PROTOCOL 100 -SERIAL5_BAUD 57 -SERIAL5_PROTOCOL -1 -SERVO1_FUNCTION 33 -SERVO2_FUNCTION 34 -SERVO3_FUNCTION 36 -SERVO4_FUNCTION 35 -SYSID_MYGCS 255 -TERRAIN_ENABLE 0 -WPNAV_ACCEL 150 -WPNAV_ACCEL_Z 100 -WPNAV_RADIUS 200 -WPNAV_SPEED 1600 -WPNAV_SPEED_DN 400 -WPNAV_SPEED_UP 400 -COMPASS_ORIENT 35 -MOT_THST_HOVER 0.185 -ATC_RAT_PIT_I 0.1 -FS_EKF_ACTION 4 -COMPASS_PRIMARY 1 -FS_EKF_THRESH 0.8 -COMPASS_DEV_ID2 73475 -COMPASS_MOT2_X 1.87 -COMPASS_MOT2_Y 0.45 -COMPASS_MOT2_Z -1.05 -COMPASS_ORIENT2 36 -COMPASS_TYPEMASK 63423 -EK2_ALT_SOURCE 2 -GPS_AUTO_SWITCH 1 -GPS_POS2_X 0.182 -GPS_POS2_Y 0.05 -GPS_POS2_Z -0.04 -GPS_TYPE2 2 -INS_LOG_BAT_MASK 5 -BATT_AMP_PERVLT 45 -BATT_LOW_VOLT 36 -BATT_FS_LOW_ACT 0 -BATT_LOW_MAH 0 -LOIT_ANG_MAX 20 -PSC_ACCZ_D 0 -PSC_ACCZ_FF 0 -PSC_ACCZ_FLTE 20 -PSC_ACCZ_I 0.5 -PSC_ACCZ_IMAX 800 -PSC_ACCZ_P 0.25 -PSC_ANGLE_MAX 0 -PSC_POSXY_P 1.2 -PSC_POSZ_P 1 -PSC_VELXY_D 0.35 -PSC_VELXY_D_FILT 5 -PSC_VELXY_FILT 5 -PSC_VELXY_I 1.2 -PSC_VELXY_IMAX 1000 -PSC_VELXY_P 1.2 -PSC_VELZ_P 3.5 -BATT_CRT_VOLT 0 -PILOT_SPEED_UP 300 -ATC_INPUT_TC 0.0833 -LOIT_BRK_JERK 3400 -LOIT_ACC_MAX 350 -LOIT_SPEED 750 -BRD_SAFETYOPTION 0 -INS_LOG_BAT_OPT 1 -LOG_BITMASK 65535 -ARM_GPS_HACC 2 -ARM_GPS_VACC 2 -LOG_BACKEND_TYPE 1 -TOFF_ALT_CHANGE 2 -TOFF_BARO_DIP 2 -TOFF_HOV_PCT 80 -TOFF_POS_CHANGE 2 -WP_NAVALT_MAX 3 -ESC_CALIBRATION 9 -ADSB_ENABLE 1 -ADSB_LIST_RADIUS 10000 +AHRS_EKF_TYPE 2 +AHRS_ORIENTATION 2 +ANGLE_MAX 2000 +ARMING_CHECK 16318 +ATC_ACCEL_P_MAX 36000 +ATC_ACCEL_R_MAX 36000 +ATC_ACCEL_Y_MAX 10000 +ATC_ANG_LIM_TC 3 +ATC_ANG_PIT_P 6 +ATC_ANG_RLL_P 6 +ATC_ANG_YAW_P 5 +ATC_RAT_PIT_D 0.012 +ATC_RAT_PIT_FLTD 6 +ATC_RAT_PIT_FLTT 6 +ATC_RAT_PIT_IMAX 0.444 +ATC_RAT_PIT_P 0.055 +ATC_RAT_RLL_D 0.012 +ATC_RAT_RLL_FLTD 6 +ATC_RAT_RLL_FLTT 6 +ATC_RAT_RLL_I 0.1 +ATC_RAT_RLL_IMAX 0.444 +ATC_RAT_RLL_P 0.055 +ATC_RAT_YAW_D 0 +ATC_RAT_YAW_FLTE 1.617667 +ATC_RAT_YAW_I 0.088756 +ATC_RAT_YAW_IMAX 0.222 +ATC_RAT_YAW_P 0.4435 +ATC_SLEW_YAW 1500 +ATC_THR_MIX_MAX 0.5 +ATC_THR_MIX_MIN 0.1 +BATT_CAPACITY 13000 +BATT_MONITOR 20 +BATT_VOLT_MULT 22.7 +BRD_SAFETYENABLE 0 +BRD_SAFETY_MASK 0 +BRD_SER1_RTSCTS 2 +BRD_SER2_RTSCTS 2 +CAN_D1_UC_ESC_BM 0 +CAN_D1_UC_SRV_BM 0 +CAN_P1_BITRATE 1000000 +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 0 +CAN_D2_UC_ESC_BM 0 +CAN_D2_UC_SRV_BM 0 +RC7_OPTION 0 +CHUTE_ALT_MIN 0 +CHUTE_DELAY_MS 500 +CHUTE_ENABLED 1 +CHUTE_TYPE 11 +COMPASS_LEARN 0 +COMPASS_MOTCT 2 +COMPASS_MOT_X 2.9 +COMPASS_MOT_Y -1.15 +COMPASS_MOT_Z 2.83 +COMPASS_USE 1 +COMPASS_USE2 1 +COMPASS_USE3 0 +COMPASS_SCALE 1.0 +COMPASS_SCALE2 1.17 +DISARM_DELAY 20 +EK2_ALT_M_NSE 3 +EK2_CHECK_SCALE 100 +EK2_ENABLE 1 +EK2_GBIAS_P_NSE 0.0004 +EK2_GPS_CHECK -1 +EK2_IMU_MASK 3 +EK2_MAGB_P_NSE 0.0002 +EK2_MAGE_P_NSE 0.005 +EK2_MAG_CAL 3 +EK2_RNG_USE_HGT -1 +EK2_MAG_LRN_LIM 30 +FENCE_ENABLE 0 +FLTMODE1 0 +FLTMODE2 0 +FLTMODE3 0 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 9 +FRAME_CLASS 1 +FRAME_TYPE 1 +FS_GCS_ENABLE 0 +FS_THR_ENABLE 6 +FS_THR_VALUE 0 +GND_EFFECT_COMP 1 +GPS_HDOP_GOOD 175 +GPS_POS1_X 0.182 +GPS_POS1_Y -0.05 +GPS_POS1_Z -0.04 +GPS_SAVE_CFG 2 +GPS_TYPE 2 +INS_ACCEL_FILTER 20 +INS_FAST_SAMPLE 5 +INS_GYRO_FILTER 20 +INS_GYR_CAL 0 +INS_POS1_X -0.077 +INS_POS1_Y 0 +INS_POS1_Z -0.05 +INS_POS2_X -0.077 +INS_POS2_Y 0 +INS_POS2_Z -0.05 +INS_POS3_X -0.077 +INS_POS3_Y 0 +INS_POS3_Z -0.05 +INS_TRIM_OPTION 0 +INS_USE 1 +INS_USE2 1 +INS_USE3 1 +LAND_REPOSITION 0 +LAND_SPEED 40 +LAND_SPEED_HIGH 200 +LOG_DISARMED 0 +LOG_FILE_BUFSIZE 40 +LOG_FILE_DSRMROT 1 +LOG_REPLAY 0 +MIS_RESTART 0 +MOT_BAT_CURR_MAX 60 +MOT_BAT_CURR_TC 2 +MOT_BAT_POW_MAX 2000 +MOT_BAT_VOLT_MAX 50.8 +MOT_BAT_VOLT_MIN 35 +MOT_HOVER_LEARN 0 +MOT_PWM_MAX 1940 +MOT_PWM_MIN 1060 +MOT_SAFE_DISARM 0 +MOT_SPIN_ARM 0.11 +MOT_SPIN_MAX 1 +MOT_SPIN_MIN 0.15 +MOT_THST_EXPO 0.8 +PILOT_THR_BHV 0 +PILOT_TKOFF_ALT 150 +PLND_ACC_P_NSE 2 +PLND_CAM_POS_X 0.165 +PLND_CAM_POS_Y -0.014 +PLND_CAM_POS_Z 0.151 +PLND_ENABLED 1 +PLND_LAND_OFS_X 0 +PLND_LAND_OFS_Y -2.6 +PLND_TYPE 2 +PLND_YAW_ALIGN 18000 +PSC_ACC_XY_FILT 3.5 +RC1_DZ 30 +RC1_MAX 2000 +RC1_MIN 1002 +RC1_TRIM 1500 +RC2_DZ 30 +RC2_MAX 1999 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_DZ 30 +RC3_MAX 1998 +RC3_MIN 999 +RC3_TRIM 1500 +RC4_DZ 40 +RC4_MAX 1997 +RC4_MIN 1002 +RC4_TRIM 1500 +RCMAP_PITCH 2 +RCMAP_ROLL 1 +RCMAP_THROTTLE 3 +RCMAP_YAW 4 +RNGFND1_TYPE 7 +RNGFND2_ADDR 112 +RNGFND2_MAX_CM 700 +RNGFND2_MIN_CM 20 +RNGFND2_TYPE 0 +RNGFND1_ADDR 102 +RNGFND1_GNDCLEAR 15 +RNGFND1_MAX_CM 9000 +RNGFND1_MIN_CM 0 +RNGFND1_POS_X -0.124 +RNGFND1_POS_Y -0.097 +RNGFND1_POS_Z 0.037 +RNGFND1_SCALING 1 +RNGFND1_STOP_PIN 55 +SERIAL0_BAUD 115 +SERIAL0_PROTOCOL 2 +SERIAL1_BAUD 921 +SERIAL1_PROTOCOL 1 +SERIAL2_BAUD 57 +SERIAL2_PROTOCOL 5 +SERIAL3_BAUD 38 +SERIAL3_PROTOCOL 5 +SERIAL4_BAUD 115 +SERIAL4_PROTOCOL 100 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL -1 +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 34 +SERVO3_FUNCTION 36 +SERVO4_FUNCTION 35 +SYSID_MYGCS 255 +TERRAIN_ENABLE 0 +WPNAV_ACCEL 150 +WPNAV_ACCEL_Z 75 +WPNAV_RADIUS 200 +WPNAV_SPEED 1600 +WPNAV_SPEED_DN 400 +WPNAV_SPEED_UP 400 +COMPASS_ORIENT 35 +MOT_THST_HOVER 0.185 +ATC_RAT_PIT_I 0.1 +FS_EKF_ACTION 4 +COMPASS_PRIMARY 1 +FS_EKF_THRESH 0.8 +COMPASS_MOT2_X 1.89 +COMPASS_MOT2_Y 0.37 +COMPASS_MOT2_Z -1.2 +COMPASS_ORIENT2 36 +EK2_ALT_SOURCE 2 +GPS_AUTO_SWITCH 1 +GPS_POS2_X 0.182 +GPS_POS2_Y 0.05 +GPS_POS2_Z -0.04 +GPS_TYPE2 2 +GPS_DELAY_MS2 100 +INS_LOG_BAT_MASK 0 +BATT_AMP_PERVLT 45 +BATT_LOW_VOLT 36 +BATT_FS_LOW_ACT 6 +BATT_LOW_MAH 0 +LOIT_ANG_MAX 20 +PSC_ACCZ_D 0 +PSC_ACCZ_FF 0 +PSC_ACCZ_FLTE 20 +PSC_ACCZ_I 0.5 +PSC_ACCZ_IMAX 800 +PSC_ACCZ_P 0.2 +PSC_ANGLE_MAX 0 +PSC_POSXY_P 1.35 +PSC_POSZ_P 1 +PSC_VELXY_D 0.25 +PSC_VELXY_D_FILT 5 +PSC_VELXY_FILT 5 +PSC_VELXY_I 1.2 +PSC_VELXY_IMAX 1000 +PSC_VELXY_P 1.35 +PSC_VELZ_P 2.0 +BATT_CRT_VOLT 0 +PILOT_SPEED_UP 300 +ATC_INPUT_TC 0.0833 +LOIT_BRK_JERK 3400 +LOIT_ACC_MAX 250 +LOIT_SPEED 750 +BRD_SAFETYOPTION 0 +INS_LOG_BAT_OPT 0 +LOG_BITMASK 65535 +ARM_GPS_HACC 2 +ARM_GPS_VACC 2 +LOG_BACKEND_TYPE 1 +TOFF_ALT_CHANGE 2 +TOFF_BARO_DIP 2 +TOFF_HOV_PCT 80 +TOFF_POS_CHANGE 2 +WP_NAVALT_MAX 1.5 +ESC_CALIBRATION 9 +ADSB_ENABLE 1 +ADSB_LIST_RADIUS 10000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm index 6813d2c88e..e63269317f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeBlack/defaults.parm @@ -1,258 +1,257 @@ -AHRS_EKF_TYPE 2 -AHRS_ORIENTATION 2 -AHRS_TRIM_X 0 -AHRS_TRIM_Y -0.0135 -ANGLE_MAX 2000 -ARMING_CHECK 16318 -ATC_ACCEL_P_MAX 36000 -ATC_ACCEL_R_MAX 36000 -ATC_ACCEL_Y_MAX 10000 -ATC_ANG_LIM_TC 3 -ATC_ANG_PIT_P 6 -ATC_ANG_RLL_P 6 -ATC_ANG_YAW_P 5 -ATC_RAT_PIT_D 0.012 -ATC_RAT_PIT_FLTD 6 -ATC_RAT_PIT_FLTT 6 -ATC_RAT_PIT_IMAX 0.444 -ATC_RAT_PIT_P 0.055 -ATC_RAT_RLL_D 0.012 -ATC_RAT_RLL_FLTD 6 -ATC_RAT_RLL_FLTT 6 -ATC_RAT_RLL_I 0.1 -ATC_RAT_RLL_IMAX 0.444 -ATC_RAT_RLL_P 0.055 -ATC_RAT_YAW_D 0 -ATC_RAT_YAW_FLTE 1.617667 -ATC_RAT_YAW_I 0.088756 -ATC_RAT_YAW_IMAX 0.222 -ATC_RAT_YAW_P 0.4435 -ATC_SLEW_YAW 1500 -ATC_THR_MIX_MAX 0.5 -ATC_THR_MIX_MIN 0.1 -BATT_CAPACITY 13000 -BATT_MONITOR 20 -BATT_VOLT_MULT 22.7 -BRD_SAFETYENABLE 0 -BRD_SAFETY_MASK 0 -BRD_SER1_RTSCTS 2 -BRD_SER2_RTSCTS 2 -CAN_D1_UC_ESC_BM 0 -CAN_D1_UC_SRV_BM 0 -CAN_P1_BITRATE 1000000 -CAN_P1_DRIVER 1 -CAN_P2_DRIVER 2 -CAN_D2_UC_ESC_BM 0 -CAN_D2_UC_SRV_BM 0 -RC7_OPTION 0 -CHUTE_ALT_MIN 0 -CHUTE_DELAY_MS 500 -CHUTE_ENABLED 1 -CHUTE_TYPE 11 -COMPASS_DEV_ID 592905 -COMPASS_LEARN 2 -COMPASS_MOTCT 2 -COMPASS_MOT_X 2.38 -COMPASS_MOT_Y -0.67 -COMPASS_MOT_Z 1.93 -COMPASS_USE 1 -COMPASS_USE2 1 -COMPASS_USE3 0 -DISARM_DELAY 20 -EK2_ALT_M_NSE 3 -EK2_CHECK_SCALE 100 -EK2_ENABLE 1 -EK2_GBIAS_P_NSE 0.0004 -EK2_GPS_CHECK -1 -EK2_IMU_MASK 3 -EK2_MAGB_P_NSE 0.0001 -EK2_MAGE_P_NSE 0.001 -EK2_MAG_CAL 3 -EK2_RNG_USE_HGT -1 -FENCE_ENABLE 0 -FLTMODE1 0 -FLTMODE2 0 -FLTMODE3 0 -FLTMODE4 5 -FLTMODE5 2 -FLTMODE6 9 -FRAME_CLASS 1 -FRAME_TYPE 1 -FS_GCS_ENABLE 0 -FS_THR_ENABLE 6 -FS_THR_VALUE 0 -GND_EFFECT_COMP 1 -GPS_HDOP_GOOD 175 -GPS_POS1_X 0.182 -GPS_POS1_Y -0.05 -GPS_POS1_Z -0.04 -GPS_SAVE_CFG 2 -GPS_TYPE 2 -INS_ACCEL_FILTER 20 -INS_FAST_SAMPLE 5 -INS_GYRO_FILTER 20 -INS_GYR_CAL 0 -INS_POS1_X -0.077 -INS_POS1_Y 0 -INS_POS1_Z -0.05 -INS_POS2_X -0.077 -INS_POS2_Y 0 -INS_POS2_Z -0.05 -INS_POS3_X -0.077 -INS_POS3_Y 0 -INS_POS3_Z -0.05 -INS_TRIM_OPTION 0 -INS_USE 1 -INS_USE2 1 -INS_USE3 1 -LAND_REPOSITION 0 -LAND_SPEED 50 -LAND_SPEED_HIGH 100 -LOG_DISARMED 0 -LOG_FILE_BUFSIZE 40 -LOG_FILE_DSRMROT 1 -LOG_REPLAY 0 -MIS_RESTART 0 -MOT_BAT_CURR_MAX 60 -MOT_BAT_CURR_TC 2 -MOT_BAT_POW_MAX 2000 -MOT_BAT_VOLT_MAX 50.8 -MOT_BAT_VOLT_MIN 35 -MOT_HOVER_LEARN 0 -MOT_PWM_MAX 1940 -MOT_PWM_MIN 1060 -MOT_SAFE_DISARM 0 -MOT_SPIN_ARM 0.11 -MOT_SPIN_MAX 1 -MOT_SPIN_MIN 0.15 -MOT_THST_EXPO 0.8 -PILOT_THR_BHV 0 -PILOT_TKOFF_ALT 150 -PLND_ACC_P_NSE 2 -PLND_CAM_POS_X 0.165 -PLND_CAM_POS_Y -0.014 -PLND_CAM_POS_Z 0.151 -PLND_ENABLED 1 -PLND_LAND_OFS_X 0 -PLND_LAND_OFS_Y -2.6 -PLND_TYPE 2 -PLND_YAW_ALIGN 18000 -PSC_ACC_XY_FILT 5 -RC1_DZ 30 -RC1_MAX 2000 -RC1_MIN 1002 -RC1_TRIM 1500 -RC2_DZ 30 -RC2_MAX 1999 -RC2_MIN 1000 -RC2_TRIM 1500 -RC3_DZ 30 -RC3_MAX 1998 -RC3_MIN 999 -RC3_TRIM 1500 -RC4_DZ 40 -RC4_MAX 1997 -RC4_MIN 1002 -RC4_TRIM 1500 -RCMAP_PITCH 2 -RCMAP_ROLL 1 -RCMAP_THROTTLE 3 -RCMAP_YAW 4 -RNGFND2_ADDR 112 -RNGFND2_MAX_CM 700 -RNGFND2_MIN_CM 20 -RNGFND2_TYPE 0 -RNGFND1_ADDR 102 -RNGFND1_GNDCLEAR 15 -RNGFND1_MAX_CM 12000 -RNGFND1_MIN_CM 0 -RNGFND1_POS_X -0.124 -RNGFND1_POS_Y -0.097 -RNGFND1_POS_Z 0.037 -RNGFND1_SCALING 1 -RNGFND1_STOP_PIN 55 -RNGFND1_TYPE 0 -SERIAL0_BAUD 115 -SERIAL0_PROTOCOL 1 -SERIAL1_BAUD 921 -SERIAL1_PROTOCOL 1 -SERIAL2_BAUD 57 -SERIAL2_PROTOCOL 5 -SERIAL3_BAUD 38 -SERIAL3_PROTOCOL 5 -SERIAL4_BAUD 115 -SERIAL4_PROTOCOL 100 -SERIAL5_BAUD 57 -SERIAL5_PROTOCOL -1 -SERVO1_FUNCTION 33 -SERVO2_FUNCTION 34 -SERVO3_FUNCTION 36 -SERVO4_FUNCTION 35 -SYSID_MYGCS 255 -TERRAIN_ENABLE 0 -WPNAV_ACCEL 150 -WPNAV_ACCEL_Z 100 -WPNAV_RADIUS 200 -WPNAV_SPEED 1600 -WPNAV_SPEED_DN 400 -WPNAV_SPEED_UP 400 -COMPASS_ORIENT 35 -MOT_THST_HOVER 0.185 -ATC_RAT_PIT_I 0.1 -FS_EKF_ACTION 4 -COMPASS_PRIMARY 1 -FS_EKF_THRESH 0.8 -COMPASS_DEV_ID2 73475 -COMPASS_MOT2_X 1.87 -COMPASS_MOT2_Y 0.45 -COMPASS_MOT2_Z -1.05 -COMPASS_ORIENT2 36 -COMPASS_TYPEMASK 63423 -EK2_ALT_SOURCE 2 -GPS_AUTO_SWITCH 1 -GPS_POS2_X 0.182 -GPS_POS2_Y 0.05 -GPS_POS2_Z -0.04 -GPS_TYPE2 2 -INS_LOG_BAT_MASK 5 -BATT_AMP_PERVLT 45 -BATT_LOW_VOLT 36 -BATT_FS_LOW_ACT 0 -BATT_LOW_MAH 0 -LOIT_ANG_MAX 20 -PSC_ACCZ_D 0 -PSC_ACCZ_FF 0 -PSC_ACCZ_FLTE 20 -PSC_ACCZ_I 0.5 -PSC_ACCZ_IMAX 800 -PSC_ACCZ_P 0.25 -PSC_ANGLE_MAX 0 -PSC_POSXY_P 1.2 -PSC_POSZ_P 1 -PSC_VELXY_D 0.35 -PSC_VELXY_D_FILT 5 -PSC_VELXY_FILT 5 -PSC_VELXY_I 1.2 -PSC_VELXY_IMAX 1000 -PSC_VELXY_P 1.2 -PSC_VELZ_P 3.5 -BATT_CRT_VOLT 0 -PILOT_SPEED_UP 300 -ATC_INPUT_TC 0.0833 -LOIT_BRK_JERK 3400 -LOIT_ACC_MAX 350 -LOIT_SPEED 750 -BRD_SAFETYOPTION 0 -INS_LOG_BAT_OPT 1 -LOG_BITMASK 65535 -ARM_GPS_HACC 2 -ARM_GPS_VACC 2 -LOG_BACKEND_TYPE 1 -TOFF_ALT_CHANGE 2 -TOFF_BARO_DIP 2 -TOFF_HOV_PCT 80 -TOFF_POS_CHANGE 2 -WP_NAVALT_MAX 3 -ESC_CALIBRATION 9 -ADSB_ENABLE 1 -ADSB_LIST_RADIUS 10000 +AHRS_EKF_TYPE 2 +AHRS_ORIENTATION 2 +ANGLE_MAX 2000 +ARMING_CHECK 16318 +ATC_ACCEL_P_MAX 36000 +ATC_ACCEL_R_MAX 36000 +ATC_ACCEL_Y_MAX 10000 +ATC_ANG_LIM_TC 3 +ATC_ANG_PIT_P 6 +ATC_ANG_RLL_P 6 +ATC_ANG_YAW_P 5 +ATC_RAT_PIT_D 0.012 +ATC_RAT_PIT_FLTD 6 +ATC_RAT_PIT_FLTT 6 +ATC_RAT_PIT_IMAX 0.444 +ATC_RAT_PIT_P 0.055 +ATC_RAT_RLL_D 0.012 +ATC_RAT_RLL_FLTD 6 +ATC_RAT_RLL_FLTT 6 +ATC_RAT_RLL_I 0.1 +ATC_RAT_RLL_IMAX 0.444 +ATC_RAT_RLL_P 0.055 +ATC_RAT_YAW_D 0 +ATC_RAT_YAW_FLTE 1.617667 +ATC_RAT_YAW_I 0.088756 +ATC_RAT_YAW_IMAX 0.222 +ATC_RAT_YAW_P 0.4435 +ATC_SLEW_YAW 1500 +ATC_THR_MIX_MAX 0.5 +ATC_THR_MIX_MIN 0.1 +BATT_CAPACITY 13000 +BATT_MONITOR 20 +BATT_VOLT_MULT 22.7 +BRD_SAFETYENABLE 0 +BRD_SAFETY_MASK 0 +BRD_SER1_RTSCTS 2 +BRD_SER2_RTSCTS 2 +CAN_D1_UC_ESC_BM 0 +CAN_D1_UC_SRV_BM 0 +CAN_P1_BITRATE 1000000 +CAN_P1_DRIVER 1 +CAN_P2_DRIVER 0 +CAN_D2_UC_ESC_BM 0 +CAN_D2_UC_SRV_BM 0 +RC7_OPTION 0 +CHUTE_ALT_MIN 0 +CHUTE_DELAY_MS 500 +CHUTE_ENABLED 1 +CHUTE_TYPE 11 +COMPASS_LEARN 0 +COMPASS_MOTCT 2 +COMPASS_MOT_X 2.9 +COMPASS_MOT_Y -1.15 +COMPASS_MOT_Z 2.83 +COMPASS_USE 1 +COMPASS_USE2 1 +COMPASS_USE3 0 +COMPASS_SCALE 1.0 +COMPASS_SCALE2 1.17 +DISARM_DELAY 20 +EK2_ALT_M_NSE 3 +EK2_CHECK_SCALE 100 +EK2_ENABLE 1 +EK2_GBIAS_P_NSE 0.0004 +EK2_GPS_CHECK -1 +EK2_IMU_MASK 3 +EK2_MAGB_P_NSE 0.0002 +EK2_MAGE_P_NSE 0.005 +EK2_MAG_CAL 3 +EK2_RNG_USE_HGT -1 +EK2_MAG_LRN_LIM 30 +FENCE_ENABLE 0 +FLTMODE1 0 +FLTMODE2 0 +FLTMODE3 0 +FLTMODE4 5 +FLTMODE5 2 +FLTMODE6 9 +FRAME_CLASS 1 +FRAME_TYPE 1 +FS_GCS_ENABLE 0 +FS_THR_ENABLE 6 +FS_THR_VALUE 0 +GND_EFFECT_COMP 1 +GPS_HDOP_GOOD 175 +GPS_POS1_X 0.182 +GPS_POS1_Y -0.05 +GPS_POS1_Z -0.04 +GPS_SAVE_CFG 2 +GPS_TYPE 2 +INS_ACCEL_FILTER 20 +INS_FAST_SAMPLE 5 +INS_GYRO_FILTER 20 +INS_GYR_CAL 0 +INS_POS1_X -0.077 +INS_POS1_Y 0 +INS_POS1_Z -0.05 +INS_POS2_X -0.077 +INS_POS2_Y 0 +INS_POS2_Z -0.05 +INS_POS3_X -0.077 +INS_POS3_Y 0 +INS_POS3_Z -0.05 +INS_TRIM_OPTION 0 +INS_USE 1 +INS_USE2 1 +INS_USE3 1 +LAND_REPOSITION 0 +LAND_SPEED 40 +LAND_SPEED_HIGH 200 +LOG_DISARMED 0 +LOG_FILE_BUFSIZE 40 +LOG_FILE_DSRMROT 1 +LOG_REPLAY 0 +MIS_RESTART 0 +MOT_BAT_CURR_MAX 60 +MOT_BAT_CURR_TC 2 +MOT_BAT_POW_MAX 2000 +MOT_BAT_VOLT_MAX 50.8 +MOT_BAT_VOLT_MIN 35 +MOT_HOVER_LEARN 0 +MOT_PWM_MAX 1940 +MOT_PWM_MIN 1060 +MOT_SAFE_DISARM 0 +MOT_SPIN_ARM 0.11 +MOT_SPIN_MAX 1 +MOT_SPIN_MIN 0.15 +MOT_THST_EXPO 0.8 +PILOT_THR_BHV 0 +PILOT_TKOFF_ALT 150 +PLND_ACC_P_NSE 2 +PLND_CAM_POS_X 0.165 +PLND_CAM_POS_Y -0.014 +PLND_CAM_POS_Z 0.151 +PLND_ENABLED 1 +PLND_LAND_OFS_X 0 +PLND_LAND_OFS_Y -2.6 +PLND_TYPE 2 +PLND_YAW_ALIGN 18000 +PSC_ACC_XY_FILT 3.5 +RC1_DZ 30 +RC1_MAX 2000 +RC1_MIN 1002 +RC1_TRIM 1500 +RC2_DZ 30 +RC2_MAX 1999 +RC2_MIN 1000 +RC2_TRIM 1500 +RC3_DZ 30 +RC3_MAX 1998 +RC3_MIN 999 +RC3_TRIM 1500 +RC4_DZ 40 +RC4_MAX 1997 +RC4_MIN 1002 +RC4_TRIM 1500 +RCMAP_PITCH 2 +RCMAP_ROLL 1 +RCMAP_THROTTLE 3 +RCMAP_YAW 4 +RNGFND1_TYPE 7 +RNGFND2_ADDR 112 +RNGFND2_MAX_CM 700 +RNGFND2_MIN_CM 20 +RNGFND2_TYPE 0 +RNGFND1_ADDR 102 +RNGFND1_GNDCLEAR 15 +RNGFND1_MAX_CM 9000 +RNGFND1_MIN_CM 0 +RNGFND1_POS_X -0.124 +RNGFND1_POS_Y -0.097 +RNGFND1_POS_Z 0.037 +RNGFND1_SCALING 1 +RNGFND1_STOP_PIN 55 +SERIAL0_BAUD 115 +SERIAL0_PROTOCOL 2 +SERIAL1_BAUD 921 +SERIAL1_PROTOCOL 1 +SERIAL2_BAUD 57 +SERIAL2_PROTOCOL 5 +SERIAL3_BAUD 38 +SERIAL3_PROTOCOL 5 +SERIAL4_BAUD 115 +SERIAL4_PROTOCOL 100 +SERIAL5_BAUD 57 +SERIAL5_PROTOCOL -1 +SERVO1_FUNCTION 33 +SERVO2_FUNCTION 34 +SERVO3_FUNCTION 36 +SERVO4_FUNCTION 35 +SYSID_MYGCS 255 +TERRAIN_ENABLE 0 +WPNAV_ACCEL 150 +WPNAV_ACCEL_Z 75 +WPNAV_RADIUS 200 +WPNAV_SPEED 1600 +WPNAV_SPEED_DN 400 +WPNAV_SPEED_UP 400 +COMPASS_ORIENT 35 +MOT_THST_HOVER 0.185 +ATC_RAT_PIT_I 0.1 +FS_EKF_ACTION 4 +COMPASS_PRIMARY 1 +FS_EKF_THRESH 0.8 +COMPASS_MOT2_X 1.89 +COMPASS_MOT2_Y 0.37 +COMPASS_MOT2_Z -1.2 +COMPASS_ORIENT2 36 +EK2_ALT_SOURCE 2 +GPS_AUTO_SWITCH 1 +GPS_POS2_X 0.182 +GPS_POS2_Y 0.05 +GPS_POS2_Z -0.04 +GPS_TYPE2 2 +GPS_DELAY_MS2 100 +INS_LOG_BAT_MASK 0 +BATT_AMP_PERVLT 45 +BATT_LOW_VOLT 36 +BATT_FS_LOW_ACT 6 +BATT_LOW_MAH 0 +LOIT_ANG_MAX 20 +PSC_ACCZ_D 0 +PSC_ACCZ_FF 0 +PSC_ACCZ_FLTE 20 +PSC_ACCZ_I 0.5 +PSC_ACCZ_IMAX 800 +PSC_ACCZ_P 0.2 +PSC_ANGLE_MAX 0 +PSC_POSXY_P 1.35 +PSC_POSZ_P 1 +PSC_VELXY_D 0.25 +PSC_VELXY_D_FILT 5 +PSC_VELXY_FILT 5 +PSC_VELXY_I 1.2 +PSC_VELXY_IMAX 1000 +PSC_VELXY_P 1.35 +PSC_VELZ_P 2.0 +BATT_CRT_VOLT 0 +PILOT_SPEED_UP 300 +ATC_INPUT_TC 0.0833 +LOIT_BRK_JERK 3400 +LOIT_ACC_MAX 250 +LOIT_SPEED 750 +BRD_SAFETYOPTION 0 +INS_LOG_BAT_OPT 0 +LOG_BITMASK 65535 +ARM_GPS_HACC 2 +ARM_GPS_VACC 2 +LOG_BACKEND_TYPE 1 +TOFF_ALT_CHANGE 2 +TOFF_BARO_DIP 2 +TOFF_HOV_PCT 80 +TOFF_POS_CHANGE 2 +WP_NAVALT_MAX 1.5 +ESC_CALIBRATION 9 +ADSB_ENABLE 1 +ADSB_LIST_RADIUS 10000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index 6813d2c88e..f150ac00ba 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -1,7 +1,5 @@ AHRS_EKF_TYPE 2 AHRS_ORIENTATION 2 -AHRS_TRIM_X 0 -AHRS_TRIM_Y -0.0135 ANGLE_MAX 2000 ARMING_CHECK 16318 ATC_ACCEL_P_MAX 36000 @@ -41,7 +39,7 @@ CAN_D1_UC_ESC_BM 0 CAN_D1_UC_SRV_BM 0 CAN_P1_BITRATE 1000000 CAN_P1_DRIVER 1 -CAN_P2_DRIVER 2 +CAN_P2_DRIVER 0 CAN_D2_UC_ESC_BM 0 CAN_D2_UC_SRV_BM 0 RC7_OPTION 0 @@ -49,15 +47,16 @@ CHUTE_ALT_MIN 0 CHUTE_DELAY_MS 500 CHUTE_ENABLED 1 CHUTE_TYPE 11 -COMPASS_DEV_ID 592905 -COMPASS_LEARN 2 +COMPASS_LEARN 0 COMPASS_MOTCT 2 -COMPASS_MOT_X 2.38 -COMPASS_MOT_Y -0.67 -COMPASS_MOT_Z 1.93 +COMPASS_MOT_X 2.9 +COMPASS_MOT_Y -1.15 +COMPASS_MOT_Z 2.83 COMPASS_USE 1 COMPASS_USE2 1 COMPASS_USE3 0 +COMPASS_SCALE 1.0 +COMPASS_SCALE2 1.17 DISARM_DELAY 20 EK2_ALT_M_NSE 3 EK2_CHECK_SCALE 100 @@ -65,10 +64,11 @@ EK2_ENABLE 1 EK2_GBIAS_P_NSE 0.0004 EK2_GPS_CHECK -1 EK2_IMU_MASK 3 -EK2_MAGB_P_NSE 0.0001 -EK2_MAGE_P_NSE 0.001 +EK2_MAGB_P_NSE 0.0002 +EK2_MAGE_P_NSE 0.005 EK2_MAG_CAL 3 EK2_RNG_USE_HGT -1 +EK2_MAG_LRN_LIM 30 FENCE_ENABLE 0 FLTMODE1 0 FLTMODE2 0 @@ -106,10 +106,10 @@ INS_USE 1 INS_USE2 1 INS_USE3 1 LAND_REPOSITION 0 -LAND_SPEED 50 -LAND_SPEED_HIGH 100 +LAND_SPEED 40 +LAND_SPEED_HIGH 200 LOG_DISARMED 0 -LOG_FILE_BUFSIZE 40 +LOG_FILE_BUFSIZE 60 LOG_FILE_DSRMROT 1 LOG_REPLAY 0 MIS_RESTART 0 @@ -137,7 +137,7 @@ PLND_LAND_OFS_X 0 PLND_LAND_OFS_Y -2.6 PLND_TYPE 2 PLND_YAW_ALIGN 18000 -PSC_ACC_XY_FILT 5 +PSC_ACC_XY_FILT 3.5 RC1_DZ 30 RC1_MAX 2000 RC1_MIN 1002 @@ -158,22 +158,22 @@ RCMAP_PITCH 2 RCMAP_ROLL 1 RCMAP_THROTTLE 3 RCMAP_YAW 4 +RNGFND1_TYPE 7 RNGFND2_ADDR 112 RNGFND2_MAX_CM 700 RNGFND2_MIN_CM 20 RNGFND2_TYPE 0 RNGFND1_ADDR 102 RNGFND1_GNDCLEAR 15 -RNGFND1_MAX_CM 12000 +RNGFND1_MAX_CM 9000 RNGFND1_MIN_CM 0 RNGFND1_POS_X -0.124 RNGFND1_POS_Y -0.097 RNGFND1_POS_Z 0.037 RNGFND1_SCALING 1 RNGFND1_STOP_PIN 55 -RNGFND1_TYPE 0 SERIAL0_BAUD 115 -SERIAL0_PROTOCOL 1 +SERIAL0_PROTOCOL 2 SERIAL1_BAUD 921 SERIAL1_PROTOCOL 1 SERIAL2_BAUD 57 @@ -191,7 +191,7 @@ SERVO4_FUNCTION 35 SYSID_MYGCS 255 TERRAIN_ENABLE 0 WPNAV_ACCEL 150 -WPNAV_ACCEL_Z 100 +WPNAV_ACCEL_Z 75 WPNAV_RADIUS 200 WPNAV_SPEED 1600 WPNAV_SPEED_DN 400 @@ -202,22 +202,21 @@ ATC_RAT_PIT_I 0.1 FS_EKF_ACTION 4 COMPASS_PRIMARY 1 FS_EKF_THRESH 0.8 -COMPASS_DEV_ID2 73475 -COMPASS_MOT2_X 1.87 -COMPASS_MOT2_Y 0.45 -COMPASS_MOT2_Z -1.05 +COMPASS_MOT2_X 1.89 +COMPASS_MOT2_Y 0.37 +COMPASS_MOT2_Z -1.2 COMPASS_ORIENT2 36 -COMPASS_TYPEMASK 63423 EK2_ALT_SOURCE 2 GPS_AUTO_SWITCH 1 GPS_POS2_X 0.182 GPS_POS2_Y 0.05 GPS_POS2_Z -0.04 GPS_TYPE2 2 -INS_LOG_BAT_MASK 5 +GPS_DELAY_MS2 100 +INS_LOG_BAT_MASK 0 BATT_AMP_PERVLT 45 BATT_LOW_VOLT 36 -BATT_FS_LOW_ACT 0 +BATT_FS_LOW_ACT 6 BATT_LOW_MAH 0 LOIT_ANG_MAX 20 PSC_ACCZ_D 0 @@ -225,25 +224,25 @@ PSC_ACCZ_FF 0 PSC_ACCZ_FLTE 20 PSC_ACCZ_I 0.5 PSC_ACCZ_IMAX 800 -PSC_ACCZ_P 0.25 +PSC_ACCZ_P 0.2 PSC_ANGLE_MAX 0 -PSC_POSXY_P 1.2 +PSC_POSXY_P 1.35 PSC_POSZ_P 1 -PSC_VELXY_D 0.35 +PSC_VELXY_D 0.25 PSC_VELXY_D_FILT 5 PSC_VELXY_FILT 5 PSC_VELXY_I 1.2 PSC_VELXY_IMAX 1000 -PSC_VELXY_P 1.2 -PSC_VELZ_P 3.5 +PSC_VELXY_P 1.35 +PSC_VELZ_P 2.0 BATT_CRT_VOLT 0 PILOT_SPEED_UP 300 ATC_INPUT_TC 0.0833 LOIT_BRK_JERK 3400 -LOIT_ACC_MAX 350 +LOIT_ACC_MAX 250 LOIT_SPEED 750 BRD_SAFETYOPTION 0 -INS_LOG_BAT_OPT 1 +INS_LOG_BAT_OPT 0 LOG_BITMASK 65535 ARM_GPS_HACC 2 ARM_GPS_VACC 2 @@ -252,7 +251,7 @@ TOFF_ALT_CHANGE 2 TOFF_BARO_DIP 2 TOFF_HOV_PCT 80 TOFF_POS_CHANGE 2 -WP_NAVALT_MAX 3 +WP_NAVALT_MAX 1.5 ESC_CALIBRATION 9 ADSB_ENABLE 1 ADSB_LIST_RADIUS 10000 From bb2b73e277c45afbb587ef9c0c47df2c87316882 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Apr 2020 10:21:13 +1000 Subject: [PATCH 134/155] HAL_ChibiOS: disable internal compasses on MttrCubeOrange --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat index 1b9d89b209..69f106ad5d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/hwdef.dat @@ -7,6 +7,12 @@ define SPRAYER_ENABLED DISABLED define GRIPPER_ENABLED DISABLED define WINCH_ENABLED DISABLED +# disable internal compasses +undef COMPASS + +# this is a dummy so we don't fall back to the AP_FEATURE_BOARD_DETECT compass list +COMPASS LSM303D SPI:lsm9ds0_ext_am ROTATION_YAW_270 + # increase arming delay define ARMING_DELAY_SEC 3.0f From b865785acfd5a3cd3882f41b45174350c31cb07a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Apr 2020 11:31:15 +1000 Subject: [PATCH 135/155] HAL_ChibiOS: fixed INS_FAST_SAMPLE for MttrCubeOrange --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index f150ac00ba..6edf22ef43 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -89,7 +89,7 @@ GPS_POS1_Z -0.04 GPS_SAVE_CFG 2 GPS_TYPE 2 INS_ACCEL_FILTER 20 -INS_FAST_SAMPLE 5 +INS_FAST_SAMPLE 7 INS_GYRO_FILTER 20 INS_GYR_CAL 0 INS_POS1_X -0.077 From 16da78ee49c29640f023effbca47222ab0839595 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Apr 2020 12:04:32 +1000 Subject: [PATCH 136/155] HAL_ChibiOS: enable harmonic notch for MttCubeOrange --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index 6edf22ef43..a29408610c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -105,6 +105,10 @@ INS_TRIM_OPTION 0 INS_USE 1 INS_USE2 1 INS_USE3 1 +INS_HNTCH_ENABLE 1 +INS_HNTCH_FREQ 110 +INS_HNTCH_BW 55 +INS_HNTCH_ATT 30 LAND_REPOSITION 0 LAND_SPEED 40 LAND_SPEED_HIGH 200 From 7a2aa664fdf80f9800883da8584df333c94e1fb1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Apr 2020 12:04:48 +1000 Subject: [PATCH 137/155] HAL_SITL: disable stack checks on SITL these are not working --- libraries/AP_HAL_SITL/Scheduler.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 2667f4ff48..db4705640f 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -344,6 +344,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ */ void Scheduler::check_thread_stacks(void) { +#if 0 WITH_SEMAPHORE(_thread_sem); for (struct thread_attr *p=threads; p; p=p->next) { const uint8_t ncheck = 8; @@ -353,4 +354,5 @@ void Scheduler::check_thread_stacks(void) } } } +#endif } From 29c76603a5b5df47855824a2ae17df127214c67f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Apr 2020 12:06:18 +1000 Subject: [PATCH 138/155] HAL_ChibiOS: removed unused params in MttrCubeOrange --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index a29408610c..b5d63fdd4a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -40,8 +40,6 @@ CAN_D1_UC_SRV_BM 0 CAN_P1_BITRATE 1000000 CAN_P1_DRIVER 1 CAN_P2_DRIVER 0 -CAN_D2_UC_ESC_BM 0 -CAN_D2_UC_SRV_BM 0 RC7_OPTION 0 CHUTE_ALT_MIN 0 CHUTE_DELAY_MS 500 From abdb25eb36ddf4083aeaf2538563b222e000b707 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 Apr 2020 11:52:00 +1000 Subject: [PATCH 139/155] HAL_ChibiOS: adjust filter params for MttrCubeOrange based on flight test --- .../hwdef/MttrCubeOrange/defaults.parm | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index b5d63fdd4a..e3b5239d5f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -10,18 +10,19 @@ ATC_ANG_PIT_P 6 ATC_ANG_RLL_P 6 ATC_ANG_YAW_P 5 ATC_RAT_PIT_D 0.012 -ATC_RAT_PIT_FLTD 6 -ATC_RAT_PIT_FLTT 6 +ATC_RAT_PIT_FLTD 10 +ATC_RAT_PIT_FLTT 10 ATC_RAT_PIT_IMAX 0.444 ATC_RAT_PIT_P 0.055 ATC_RAT_RLL_D 0.012 -ATC_RAT_RLL_FLTD 6 -ATC_RAT_RLL_FLTT 6 +ATC_RAT_RLL_FLTD 10 +ATC_RAT_RLL_FLTT 10 ATC_RAT_RLL_I 0.1 ATC_RAT_RLL_IMAX 0.444 ATC_RAT_RLL_P 0.055 ATC_RAT_YAW_D 0 ATC_RAT_YAW_FLTE 1.617667 +ATC_RAT_YAW_FLTT 10 ATC_RAT_YAW_I 0.088756 ATC_RAT_YAW_IMAX 0.222 ATC_RAT_YAW_P 0.4435 @@ -104,9 +105,10 @@ INS_USE 1 INS_USE2 1 INS_USE3 1 INS_HNTCH_ENABLE 1 -INS_HNTCH_FREQ 110 -INS_HNTCH_BW 55 -INS_HNTCH_ATT 30 +INS_HNTCH_FREQ 63 +INS_HNTCH_BW 40 +INS_HNTCH_ATT 40 +INS_HNTCH_REF 0.1785 LAND_REPOSITION 0 LAND_SPEED 40 LAND_SPEED_HIGH 200 From 19de31a287bb9f52db705afdfec1b3ed41748372 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Apr 2020 09:02:40 +1000 Subject: [PATCH 140/155] HAL_ChibiOS: tweak MttrCubeOrange harmonic notch based on flight log --- .../AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index e3b5239d5f..cb911177e2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -105,10 +105,12 @@ INS_USE 1 INS_USE2 1 INS_USE3 1 INS_HNTCH_ENABLE 1 -INS_HNTCH_FREQ 63 -INS_HNTCH_BW 40 +INS_HNTCH_FREQ 56 +INS_HNTCH_BW 37 INS_HNTCH_ATT 40 -INS_HNTCH_REF 0.1785 +INS_HNTCH_REF 0.193 +INS_HNTCH_MODE 1 +INS_HNTCH_HMNCS 15 LAND_REPOSITION 0 LAND_SPEED 40 LAND_SPEED_HIGH 200 From 93b7dd72593b48f3598a01a1d5a8c5d5523ca32d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Apr 2020 12:48:57 +1000 Subject: [PATCH 141/155] AP_GPS: added GPS_DRV_OPTIONS for using SERIALn_BAUD instead of auto-baud list --- libraries/AP_GPS/AP_GPS.cpp | 25 ++++++++++++++++++++++--- libraries/AP_GPS/AP_GPS.h | 8 ++++++++ libraries/AP_GPS/GPS_Backend.cpp | 2 +- 3 files changed, 31 insertions(+), 4 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 8d6395fba8..68552a8822 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -284,6 +284,13 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { AP_GROUPINFO("BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f), #endif + // @Param: DRV_OPTIONS + // @DisplayName: driver options + // @Description: Additional backend specific options + // @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use SERIALn_BAUD instead of auto-bauding + // @User: Advanced + AP_GROUPINFO("DRV_OPTIONS", 22, AP_GPS, _driver_options, 0), + AP_GROUPEND }; @@ -446,6 +453,18 @@ void AP_GPS::send_blob_update(uint8_t instance) } } +/* + get baudrate for a probe step + */ +uint32_t AP_GPS::get_baudrate(uint8_t instance, uint8_t step) const +{ + if (unsigned(_driver_options.get()) & unsigned(DRV_OPTIONS::NO_AUTOBAUD)) { + // use SERIALn_BAUD, ignoring _baudrates array + return AP::serialmanager().find_baudrate(AP_SerialManager::SerialProtocol_GPS, instance); + } + return _baudrates[step]; +} + /* run detection step for one GPS instance. If this finds a GPS then it will fill in drivers[instance] and change state[instance].status @@ -521,7 +540,7 @@ void AP_GPS::detect_instance(uint8_t instance) if (dstate->current_baud == ARRAY_SIZE(_baudrates)) { dstate->current_baud = 0; } - uint32_t baudrate = _baudrates[dstate->current_baud]; + uint32_t baudrate = get_baudrate(instance, dstate->current_baud); _port[instance]->begin(baudrate); _port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); dstate->last_baud_change_ms = now; @@ -550,8 +569,8 @@ void AP_GPS::detect_instance(uint8_t instance) for. */ if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) && - ((!_auto_config && _baudrates[dstate->current_baud] >= 38400) || - _baudrates[dstate->current_baud] == 115200) && + ((!_auto_config && get_baudrate(instance, dstate->current_baud) >= 38400) || + get_baudrate(instance, dstate->current_baud) == 115200) && AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) { new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]); } diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 79acc60c7c..e2155f051e 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -466,7 +466,14 @@ class AP_GPS AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]; AP_Int8 _blend_mask; AP_Float _blend_tc; + AP_Int16 _driver_options; + // GPS_DRV_OPTIONS bits + enum class DRV_OPTIONS { + MB_USE_UART2 = 1U<<0, + NO_AUTOBAUD = 1U<<1, + }; + uint32_t _log_gps_bit = -1; private: @@ -527,6 +534,7 @@ class AP_GPS static const char _initialisation_blob[]; static const char _initialisation_raw_blob[]; + uint32_t get_baudrate(uint8_t instance, uint8_t step) const; void detect_instance(uint8_t instance); void update_instance(uint8_t instance); diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 1a64e3730f..81ef664f4e 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -147,7 +147,7 @@ void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) cons "GPS %d: detected as %s at %d baud", instance + 1, name(), - gps._baudrates[dstate.current_baud]); + gps.get_baudrate(instance, dstate.current_baud)); } else { hal.util->snprintf(buffer, buflen, "GPS %d: specified as %s", From 9b836347a308ca6d6f87b9256b06ceffb9dc2bfc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Apr 2020 15:04:11 +1000 Subject: [PATCH 142/155] HAL_ChibiOS: adjust PID tuning for MttrCubeOrange --- .../AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index cb911177e2..b8c73c2856 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -9,23 +9,23 @@ ATC_ANG_LIM_TC 3 ATC_ANG_PIT_P 6 ATC_ANG_RLL_P 6 ATC_ANG_YAW_P 5 -ATC_RAT_PIT_D 0.012 +ATC_RAT_PIT_D 0.01 ATC_RAT_PIT_FLTD 10 ATC_RAT_PIT_FLTT 10 ATC_RAT_PIT_IMAX 0.444 -ATC_RAT_PIT_P 0.055 -ATC_RAT_RLL_D 0.012 +ATC_RAT_PIT_P 0.11 +ATC_RAT_RLL_D 0.01 ATC_RAT_RLL_FLTD 10 ATC_RAT_RLL_FLTT 10 ATC_RAT_RLL_I 0.1 ATC_RAT_RLL_IMAX 0.444 -ATC_RAT_RLL_P 0.055 +ATC_RAT_RLL_P 0.1 ATC_RAT_YAW_D 0 ATC_RAT_YAW_FLTE 1.617667 ATC_RAT_YAW_FLTT 10 ATC_RAT_YAW_I 0.088756 ATC_RAT_YAW_IMAX 0.222 -ATC_RAT_YAW_P 0.4435 +ATC_RAT_YAW_P 0.8 ATC_SLEW_YAW 1500 ATC_THR_MIX_MAX 0.5 ATC_THR_MIX_MIN 0.1 From 77e24d6a1c95e7827dc421a49867bfc26a032279 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 May 2020 08:16:57 +1000 Subject: [PATCH 143/155] AP_RangeFinder: fixed mixing UAVCAN and non-UAVCAN rangefinders UAVCAN rangefinders add themselves to the frontend drivers as the devices appear. If they turn up before RangeFinder::init() is run then this prevented init() from scanning for the other rangefinders as num_instances is non-zero This also fixes a race condition in updating num_instances in the UAVCAN backend --- .../AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp | 21 ++++++++++-------- libraries/AP_RangeFinder/RangeFinder.cpp | 22 ++++++++++++++++--- libraries/AP_RangeFinder/RangeFinder.h | 2 ++ 3 files changed, 33 insertions(+), 12 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp index e05adf9359..6cca731087 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_UAVCAN.cpp @@ -49,11 +49,12 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u 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 (AP::rangefinder()->params[i].type == RangeFinder::RangeFinder_TYPE_UAVCAN && - AP::rangefinder()->params[i].address == address) { - driver = (AP_RangeFinder_UAVCAN*)AP::rangefinder()->drivers[i]; + if (frontend.params[i].type == RangeFinder::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::RangeFinder_TYPE_UAVCAN)) { @@ -70,19 +71,21 @@ AP_RangeFinder_UAVCAN* AP_RangeFinder_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_u if (create_new) { for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) { - if (AP::rangefinder()->params[i].type == RangeFinder::RangeFinder_TYPE_UAVCAN && - AP::rangefinder()->params[i].address == address) { - if (AP::rangefinder()->drivers[i] != nullptr) { + if (frontend.params[i].type == RangeFinder::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; } - AP::rangefinder()->drivers[i] = new AP_RangeFinder_UAVCAN(AP::rangefinder()->state[i], AP::rangefinder()->params[i]); - driver = (AP_RangeFinder_UAVCAN*)AP::rangefinder()->drivers[i]; + frontend.drivers[i] = new AP_RangeFinder_UAVCAN(frontend.state[i], frontend.params[i]); + driver = (AP_RangeFinder_UAVCAN*)frontend.drivers[i]; if (driver == nullptr) { break; } - AP::rangefinder()->num_instances = MAX(i+1, AP::rangefinder()->num_instances); + 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; diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 8a4ea81f87..72860a8512 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -253,10 +253,11 @@ void RangeFinder::convert_params(void) { */ void RangeFinder::init(enum Rotation orientation_default) { - if (num_instances != 0) { + if (init_done) { // init called a 2nd time? return; } + init_done = true; convert_params(); @@ -268,11 +269,14 @@ void RangeFinder::init(enum Rotation orientation_default) for (uint8_t i=0, serial_instance = 0; i Date: Wed, 20 May 2020 15:33:06 +1000 Subject: [PATCH 144/155] AP_BLHeli: allow for negative temperatures from BLHeli32 ESCs ESCs can send negative values --- libraries/AP_BLHeli/AP_BLHeli.cpp | 2 +- libraries/AP_BLHeli/AP_BLHeli.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 08686aea62..891fad8d29 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -1363,7 +1363,7 @@ void AP_BLHeli::read_telemetry_packet(void) return; } struct telem_data td; - td.temperature = buf[0]; + td.temperature = int8_t(buf[0]); td.voltage = (buf[1]<<8) | buf[2]; td.current = (buf[3]<<8) | buf[4]; td.consumption = (buf[5]<<8) | buf[6]; diff --git a/libraries/AP_BLHeli/AP_BLHeli.h b/libraries/AP_BLHeli/AP_BLHeli.h index f397ebccec..2775a08110 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.h +++ b/libraries/AP_BLHeli/AP_BLHeli.h @@ -46,7 +46,7 @@ class AP_BLHeli { static const struct AP_Param::GroupInfo var_info[]; struct telem_data { - uint8_t temperature; // degrees C + int8_t temperature; // degrees C, negative values allowed uint16_t voltage; // volts * 100 uint16_t current; // amps * 100 uint16_t consumption;// mAh From be1b6d5b629f40b589febb8755bfdf44167e6389 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 May 2020 18:03:21 +1000 Subject: [PATCH 145/155] HAL_ChibiOS: fixed defaults for RNGFND2 --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index b8c73c2856..3e09f4be44 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -166,8 +166,8 @@ RCMAP_THROTTLE 3 RCMAP_YAW 4 RNGFND1_TYPE 7 RNGFND2_ADDR 112 -RNGFND2_MAX_CM 700 -RNGFND2_MIN_CM 20 +RNGFND2_MAX_CM 10000 +RNGFND2_MIN_CM 50 RNGFND2_TYPE 0 RNGFND1_ADDR 102 RNGFND1_GNDCLEAR 15 From 9709230543f7c657d75a526529551b0aed3805c2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 May 2020 18:05:38 +1000 Subject: [PATCH 146/155] AP_Mission: added continue after land mission option --- libraries/AP_Mission/AP_Mission.cpp | 2 +- libraries/AP_Mission/AP_Mission.h | 11 +++++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index c0eb6c40ce..d221d32ad8 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_Mission::var_info[] = { // @Param: OPTIONS // @DisplayName: Mission options bitmask // @Description: Bitmask of what options to use in missions. - // @Bitmask: 0:Clear Mission on reboot + // @Bitmask: 0:Clear Mission on reboot, 2:ContinueAfterLand // @User: Advanced AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT), diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index 54a3f93707..e5a3323953 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -39,6 +39,8 @@ #define AP_MISSION_OPTIONS_DEFAULT 0 // Do not clear the mission when rebooting #define AP_MISSION_MASK_MISSION_CLEAR (1<<0) // If set then Clear the mission on boot +#define AP_MISSION_MASK_CONTINUE_AFTER_LAND (1<<2) // Allow mission to continue after land + /// @class AP_Mission /// @brief Object managing Mission class AP_Mission { @@ -480,6 +482,15 @@ class AP_Mission { // returns true if the mission contains the requested items bool contains_item(MAV_CMD command) const; + /* + return true if MIS_OPTIONS is set to allow continue of mission + logic after a land. If this is false then after a landing is + complete the vehicle should disarm and mission logic should stop + */ + bool continue_after_land(void) const { + return (_options.get() & AP_MISSION_MASK_CONTINUE_AFTER_LAND) != 0; + } + // user settable parameters static const struct AP_Param::GroupInfo var_info[]; From 0764698fe9e42013c78af0cba3b48b4e42dfee4f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 May 2020 18:06:31 +1000 Subject: [PATCH 147/155] Copter: implement disarm on land based on MIS_OPTIONS only continue with mission if MIS_OPTIONS bit is set --- ArduCopter/mode_auto.cpp | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index e3b5f2fd04..33ff77356b 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1541,7 +1541,19 @@ bool ModeAuto::verify_land() case LandStateType_Descending: // rely on THROTTLE_LAND mode to correctly update landing status retval = copter.ap.land_complete && (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE); - gcs().send_text(MAV_SEVERITY_INFO,"Landed"); + if (retval) { + gcs().send_text(MAV_SEVERITY_INFO,"Landed"); + } + if (retval && !mission.continue_after_land() && copter.motors->armed()) { + /* + we want to stop mission processing on land + completion. Disarm now, then return false. This + leaves mission state machine in the current NAV_LAND + mission item. After disarming the mission will reset + */ + copter.arming.disarm(); + retval = false; + } break; default: From a39080fdf5ba068df941e895c06e46228be27d80 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 May 2020 18:17:53 +1000 Subject: [PATCH 148/155] HAL_ChibiOS: minor tuning adjustments for MttrCubeOrange --- libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm index 3e09f4be44..cdb9b67dc0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/MttrCubeOrange/defaults.parm @@ -2,7 +2,7 @@ AHRS_EKF_TYPE 2 AHRS_ORIENTATION 2 ANGLE_MAX 2000 ARMING_CHECK 16318 -ATC_ACCEL_P_MAX 36000 +ATC_ACCEL_P_MAX 30000 ATC_ACCEL_R_MAX 36000 ATC_ACCEL_Y_MAX 10000 ATC_ANG_LIM_TC 3 @@ -196,7 +196,7 @@ SERVO3_FUNCTION 36 SERVO4_FUNCTION 35 SYSID_MYGCS 255 TERRAIN_ENABLE 0 -WPNAV_ACCEL 150 +WPNAV_ACCEL 120 WPNAV_ACCEL_Z 75 WPNAV_RADIUS 200 WPNAV_SPEED 1600 From 93eccfdc7786c73f9f1a4c286042246c1e7adc43 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 May 2020 11:52:00 +1000 Subject: [PATCH 149/155] AP_Terrain: fixed bug in disk offset calculation this fixes a problem where two different locations could both be mapped to the same disk block in the terrain/*.DAT files. That meant that pre-filled terrain on the microSD card would sometimes require a download in flight. It also means that a RTL with loss of GCS could sometimes fly through a region with no terrain data available This fixes the issue by using a fixed stride between rows in the disk format. Other changes in this patch: - allow for a 2cm discrepancy in the lat/lon of the grid corners. This is needed to allow for slightly different floating point rounding in tools that pre-generate terrain data to load on the microSD - added TERRAIN_OPTIONS parameter to allow the user to disable attempts to download new terrain data. This is mostly useful for testing to validate a terrain generator --- libraries/AP_Terrain/AP_Terrain.cpp | 8 +++++++ libraries/AP_Terrain/AP_Terrain.h | 12 ++++++++++ libraries/AP_Terrain/TerrainGCS.cpp | 8 +++++-- libraries/AP_Terrain/TerrainIO.cpp | 34 +++++++++++++++++++--------- libraries/AP_Terrain/TerrainUtil.cpp | 12 +++++----- 5 files changed, 55 insertions(+), 19 deletions(-) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 50c67749fd..26515849ae 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -47,6 +47,13 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @User: Advanced AP_GROUPINFO("SPACING", 1, AP_Terrain, grid_spacing, 100), + // @Param: OPTIONS + // @DisplayName: Terrain options + // @Description: Options to change behaviour of terrain system + // @Bitmask: 0:Disable Download + // @User: Advanced + AP_GROUPINFO("OPTIONS", 2, AP_Terrain, options, 0), + AP_GROUPEND }; @@ -296,6 +303,7 @@ float AP_Terrain::lookahead(float bearing, float distance, float climb_ratio) */ void AP_Terrain::update(void) { + if (!enable) { return; } // just schedule any needed disk IO schedule_disk_io(); diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 10ca5aadcd..9144f307ef 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -57,7 +57,13 @@ // format of grid on disk #define TERRAIN_GRID_FORMAT_VERSION 1 +// we allow for a 2cm discrepancy in the grid corners. This is to +// account for different rounding in terrain DAT file generators using +// different programming languages +#define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= 2) + #if TERRAIN_DEBUG +#include #define ASSERT_RANGE(v,minv,maxv) assert((v)<=(maxv)&&(v)>=(minv)) #else #define ASSERT_RANGE(v,minv,maxv) @@ -325,6 +331,7 @@ class AP_Terrain { void io_timer(void); void open_file(void); void seek_offset(void); + uint32_t east_blocks(struct grid_block &block) const; void write_block(void); void read_block(void); @@ -342,6 +349,11 @@ class AP_Terrain { // parameters AP_Int8 enable; AP_Int16 grid_spacing; // meters between grid points + AP_Int16 options; // option bits + + enum class Options { + DisableDownload = (1U<<0), + }; // reference to AP_Mission, so we can ask preload terrain data for // all waypoints diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index e57a68cec6..dc719f9223 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -39,6 +39,10 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac { struct grid_block &grid = gcache.grid; + if (options.get() & uint16_t(Options::DisableDownload)) { + return false; + } + if (grid.spacing != grid_spacing) { // an invalid grid return false; @@ -263,8 +267,8 @@ void AP_Terrain::handle_terrain_data(const mavlink_message_t &msg) uint16_t i; for (i=0; iprintf("Seek %lu failed - %s\n", @@ -283,17 +289,23 @@ void AP_Terrain::read_block(void) ssize_t ret = AP::FS().read(fd, &disk_block, sizeof(disk_block)); if (ret != sizeof(disk_block) || - disk_block.block.lat != lat || - disk_block.block.lon != lon || + !TERRAIN_LATLON_EQUAL(disk_block.block.lat,lat) || + !TERRAIN_LATLON_EQUAL(disk_block.block.lon,lon) || disk_block.block.bitmap == 0 || disk_block.block.spacing != grid_spacing || disk_block.block.version != TERRAIN_GRID_FORMAT_VERSION || disk_block.block.crc != get_block_crc(disk_block.block)) { #if TERRAIN_DEBUG - printf("read empty block at %ld %ld ret=%d\n", + printf("read empty block at %ld %ld ret=%d (%ld %ld %u 0x%08lx) 0x%04x:0x%04x\n", (long)lat, (long)lon, - (int)ret); + (int)ret, + (long)disk_block.block.lat, + (long)disk_block.block.lon, + (unsigned)disk_block.block.spacing, + (unsigned long)disk_block.block.bitmap, + (unsigned)disk_block.block.crc, + (unsigned)get_block_crc(disk_block.block)); #endif // a short read or bad data is not an IO failure, just a // missing block on disk diff --git a/libraries/AP_Terrain/TerrainUtil.cpp b/libraries/AP_Terrain/TerrainUtil.cpp index dbb6278de5..34adc8e394 100644 --- a/libraries/AP_Terrain/TerrainUtil.cpp +++ b/libraries/AP_Terrain/TerrainUtil.cpp @@ -113,8 +113,8 @@ AP_Terrain::grid_cache &AP_Terrain::find_grid_cache(const struct grid_info &info // see if we have that grid for (uint16_t i=0; i Date: Fri, 1 May 2020 18:33:02 +1000 Subject: [PATCH 150/155] AP_Terrain: added script for creating terrain *.dat files useful for pre-populating a microSD card --- libraries/AP_Terrain/tools/create_terrain.py | 299 +++++++++++++++++++ 1 file changed, 299 insertions(+) create mode 100755 libraries/AP_Terrain/tools/create_terrain.py diff --git a/libraries/AP_Terrain/tools/create_terrain.py b/libraries/AP_Terrain/tools/create_terrain.py new file mode 100755 index 0000000000..75cf260704 --- /dev/null +++ b/libraries/AP_Terrain/tools/create_terrain.py @@ -0,0 +1,299 @@ +#!/usr/bin/env python +''' +create ardupilot terrain database files +''' + +from MAVProxy.modules.mavproxy_map import srtm +import math, struct, os, sys +import crc16, time, struct + +# MAVLink sends 4x4 grids +TERRAIN_GRID_MAVLINK_SIZE = 4 + +# a 2k grid_block on disk contains 8x7 of the mavlink grids. Each +# grid block overlaps by one with its neighbour. This ensures that +# the altitude at any point can be calculated from a single grid +# block +TERRAIN_GRID_BLOCK_MUL_X = 7 +TERRAIN_GRID_BLOCK_MUL_Y = 8 + +# this is the spacing between 32x28 grid blocks, in grid_spacing units +TERRAIN_GRID_BLOCK_SPACING_X = ((TERRAIN_GRID_BLOCK_MUL_X-1)*TERRAIN_GRID_MAVLINK_SIZE) +TERRAIN_GRID_BLOCK_SPACING_Y = ((TERRAIN_GRID_BLOCK_MUL_Y-1)*TERRAIN_GRID_MAVLINK_SIZE) + +# giving a total grid size of a disk grid_block of 32x28 +TERRAIN_GRID_BLOCK_SIZE_X = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_X) +TERRAIN_GRID_BLOCK_SIZE_Y = (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y) + +# format of grid on disk +TERRAIN_GRID_FORMAT_VERSION = 1 + +IO_BLOCK_SIZE = 2048 + +GRID_SPACING = 100 + +def to_float32(f): + '''emulate single precision float''' + return struct.unpack('f', struct.pack('f',f))[0] + +LOCATION_SCALING_FACTOR = to_float32(0.011131884502145034) +LOCATION_SCALING_FACTOR_INV = to_float32(89.83204953368922) + +def longitude_scale(lat): + '''get longitude scale factor''' + scale = to_float32(math.cos(to_float32(math.radians(lat)))) + return max(scale, 0.01) + +def get_distance_NE_e7(lat1, lon1, lat2, lon2): + '''get distance tuple between two positions in 1e7 format''' + return ((lat2 - lat1) * LOCATION_SCALING_FACTOR, (lon2 - lon1) * LOCATION_SCALING_FACTOR * longitude_scale(lat1*1.0e-7)) + +def add_offset(lat_e7, lon_e7, ofs_north, ofs_east): + '''add offset in meters to a position''' + dlat = int(float(ofs_north) * LOCATION_SCALING_FACTOR_INV) + dlng = int((float(ofs_east) * LOCATION_SCALING_FACTOR_INV) / longitude_scale(lat_e7*1.0e-7)) + return (int(lat_e7+dlat), int(lon_e7+dlng)) + +def east_blocks(lat_e7, lon_e7): + '''work out how many blocks per stride on disk''' + lat2_e7 = lat_e7 + lon2_e7 = lon_e7 + 10*1000*1000 + + # shift another two blocks east to ensure room is available + lat2_e7, lon2_e7 = add_offset(lat2_e7, lon2_e7, 0, 2*GRID_SPACING*TERRAIN_GRID_BLOCK_SIZE_Y) + offset = get_distance_NE_e7(lat_e7, lon_e7, lat2_e7, lon2_e7) + return int(offset[1] / (GRID_SPACING*TERRAIN_GRID_BLOCK_SPACING_Y)) + +def pos_from_file_offset(lat_degrees, lon_degrees, file_offset): + '''return a lat/lon in 1e7 format given a file offset''' + + ref_lat = int(lat_degrees*10*1000*1000) + ref_lon = int(lon_degrees*10*1000*1000) + + stride = east_blocks(ref_lat, ref_lon) + blocks = file_offset // IO_BLOCK_SIZE + grid_idx_x = blocks // stride + grid_idx_y = blocks % stride + + idx_x = grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X + idx_y = grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y + offset = (idx_x * GRID_SPACING, idx_y * GRID_SPACING) + + (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon, offset[0], offset[1]) + + offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7) + grid_idx_x = int(idx_x / TERRAIN_GRID_BLOCK_SPACING_X) + grid_idx_y = int(idx_y / TERRAIN_GRID_BLOCK_SPACING_Y) + + (lat_e7, lon_e7) = add_offset(ref_lat, ref_lon, + grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(GRID_SPACING), + grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(GRID_SPACING)) + + return (lat_e7, lon_e7) + +class GridBlock(object): + def __init__(self, lat_int, lon_int, lat, lon): + ''' + a grid block is a structure in a local file containing height + information. Each grid block is 2048 bytes in size, to keep file IO to + block oriented SD cards efficient + ''' + + # crc of whole block, taken with crc=0 + self.crc = 0 + + # format version number + self.version = TERRAIN_GRID_FORMAT_VERSION + + # grid spacing in meters + self.spacing = GRID_SPACING + + # heights in meters over a 32*28 grid + self.height = [] + for x in range(TERRAIN_GRID_BLOCK_SIZE_X): + self.height.append([0]*TERRAIN_GRID_BLOCK_SIZE_Y) + + # bitmap of 4x4 grids filled in from GCS (56 bits are used) + self.bitmap = (1<<56)-1 + + lat_e7 = int(lat * 1.0e7) + lon_e7 = int(lon * 1.0e7) + + # grids start on integer degrees. This makes storing terrain data on + # the SD card a bit easier. Note that this relies on the python floor + # behaviour with integer division + self.lat_degrees = lat_int + self.lon_degrees = lon_int + + # create reference position for this rounded degree position + ref_lat = self.lat_degrees*10*1000*1000 + ref_lon = self.lon_degrees*10*1000*1000 + + # find offset from reference + offset = get_distance_NE_e7(ref_lat, ref_lon, lat_e7, lon_e7) + + offset = (round(offset[0]), round(offset[1])) + + # get indices in terms of grid_spacing elements + idx_x = int(offset[0] / GRID_SPACING) + idx_y = int(offset[1] / GRID_SPACING) + + # find indexes into 32*28 grids for this degree reference. Note + # the use of TERRAIN_GRID_BLOCK_SPACING_{X,Y} which gives a one square + # overlap between grids + self.grid_idx_x = idx_x // TERRAIN_GRID_BLOCK_SPACING_X + self.grid_idx_y = idx_y // TERRAIN_GRID_BLOCK_SPACING_Y + + # calculate lat/lon of SW corner of 32*28 grid_block + (ref_lat, ref_lon) = add_offset(ref_lat, ref_lon, + self.grid_idx_x * TERRAIN_GRID_BLOCK_SPACING_X * float(GRID_SPACING), + self.grid_idx_y * TERRAIN_GRID_BLOCK_SPACING_Y * float(GRID_SPACING)) + self.lat = ref_lat + self.lon = ref_lon + + def fill(self, gx, gy, altitude): + '''fill a square''' + self.height[gx][gy] = int(altitude) + + def blocknum(self): + '''find IO block number''' + stride = east_blocks(self.lat_degrees*1e7, self.lon_degrees*1e7) + return stride * self.grid_idx_x + self.grid_idx_y + +class DataFile(object): + def __init__(self, lat, lon): + if lat < 0: + NS = 'S' + else: + NS = 'N' + if lon < 0: + EW = 'W' + else: + EW = 'E' + name = "terrain/%c%02u%c%03u.DAT" % (NS, min(abs(int(lat)), 99), + EW, min(abs(int(lon)), 999)) + try: + os.mkdir("terrain") + except Exception: + pass + if not os.path.exists(name): + self.fh = open(name, 'w+b') + else: + self.fh = open(name, 'r+b') + + def seek_offset(self, block): + '''seek to right offset''' + # work out how many longitude blocks there are at this latitude + file_offset = block.blocknum() * IO_BLOCK_SIZE + self.fh.seek(file_offset) + + def pack(self, block): + '''pack into a block''' + buf = bytes() + buf += struct.pack("2 or + abs(lon - block.lon)>2 or + spacing != GRID_SPACING or + bitmap != (1<<56)-1): + return False + buf = buf[:16] + struct.pack(" Date: Sun, 21 Jun 2020 18:05:33 +1000 Subject: [PATCH 151/155] AP_UAVCAN: added FastIMU reporting --- .../examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp b/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp index 160c6d4bbc..c197ef81d9 100644 --- a/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp +++ b/libraries/AP_UAVCAN/examples/UAVCAN_sniffer/UAVCAN_sniffer.cpp @@ -37,6 +37,8 @@ #include +#include + void setup(); void loop(); @@ -153,6 +155,15 @@ 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_FastIMU(const uavcan::ReceivedDataStructure& msg) { + static uint8_t last_counter; + if (msg.counter != (last_counter + 1) % 256) { + ::printf("crt %u %u\n", last_counter, msg.counter); + } + last_counter = msg.counter; + count_msg(msg.getDataTypeFullName()); +} + void UAVCAN_sniffer::init(void) { uint8_t interface = 0; @@ -226,7 +237,7 @@ void UAVCAN_sniffer::init(void) START_CB(uavcan::equipment::esc::RawCommand, RawCommand); START_CB(uavcan::equipment::indication::LightsCommand, LightsCommand); START_CB(com::hex::equipment::flow::Measurement, Measurement); - + START_CB(ardupilot::imu::FastIMU, FastIMU); /* * Informing other nodes that we're ready to work. From 41a6c193e592b639da78456efce7c2f87645bd41 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 21 Jun 2020 18:05:43 +1000 Subject: [PATCH 152/155] AP_UAVCAN: support UAVCAN IMUs --- libraries/AP_UAVCAN/AP_UAVCAN.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_UAVCAN/AP_UAVCAN.cpp b/libraries/AP_UAVCAN/AP_UAVCAN.cpp index 5336b57862..32320bb432 100644 --- a/libraries/AP_UAVCAN/AP_UAVCAN.cpp +++ b/libraries/AP_UAVCAN/AP_UAVCAN.cpp @@ -53,6 +53,7 @@ #include #include "AP_UAVCAN_Server.h" #include +#include #define LED_DELAY_US 50000 @@ -248,6 +249,7 @@ void AP_UAVCAN::init(uint8_t driver_index, bool enable_filters) AP_Airspeed_UAVCAN::subscribe_msgs(this); AP_OpticalFlow_HereFlow::subscribe_msgs(this); AP_RangeFinder_UAVCAN::subscribe_msgs(this); + AP_InertialSensor_UAVCAN::subscribe_msgs(this); act_out_array[driver_index] = new uavcan::Publisher(*_node); act_out_array[driver_index]->setTxTimeout(uavcan::MonotonicDuration::fromMSec(2)); From d0f0f0ffc86cd3926146caa62b29ae6850a294b0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 21 Jun 2020 18:06:46 +1000 Subject: [PATCH 153/155] AP_UAVCAN: added FastIMU dsdl --- .../dsdl/ardupilot/imu/20002.FastIMU.uavcan | 21 +++++++++++++++++++ 1 file changed, 21 insertions(+) create mode 100644 libraries/AP_UAVCAN/dsdl/ardupilot/imu/20002.FastIMU.uavcan diff --git a/libraries/AP_UAVCAN/dsdl/ardupilot/imu/20002.FastIMU.uavcan b/libraries/AP_UAVCAN/dsdl/ardupilot/imu/20002.FastIMU.uavcan new file mode 100644 index 0000000000..fc9151a8cd --- /dev/null +++ b/libraries/AP_UAVCAN/dsdl/ardupilot/imu/20002.FastIMU.uavcan @@ -0,0 +1,21 @@ +# +# IMU data with scale factors to keep high accuracy with low bus bandwidth cost + +# which sensor from this node +uint8 sensor_id + +# counter to detect packet loss +uint8 counter + +# the amount of time that this sample was collected over, in microseconds +uint16 time_us + +# scale factors. These vary for each packet to keep the data within the range of an int16 on all axes +uint8 accel_scale +uint8 gyro_scale + +# accelerometer data. Value in m/s/s is (10 * accel[i] * (1+accel_scale) / INT16_MAX) +int16[3] accel + +# accelerometer data. Value in rad/sec is (gyro[i] * (1+gyro_scale) / INT16_MAX) +int16[3] gyro From 0aac7576a6f614a2d681be6afe00c16af7e0d12c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Jul 2020 18:06:21 +1000 Subject: [PATCH 154/155] AP_InertialSensor: support UAVCAN IMUs --- .../AP_InertialSensor/AP_InertialSensor.cpp | 11 ++ .../AP_InertialSensor_UAVCAN.cpp | 172 ++++++++++++++++++ .../AP_InertialSensor_UAVCAN.h | 57 ++++++ 3 files changed, 240 insertions(+) create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.cpp create mode 100644 libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.h diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 35745f6733..a3d66ad983 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -23,6 +23,7 @@ #include "AP_InertialSensor_BMI055.h" #include "AP_InertialSensor_BMI088.h" #include "AP_InertialSensor_Invensensev2.h" +#include "AP_InertialSensor_UAVCAN.h" /* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop. * Output is on the debug console. */ @@ -582,6 +583,11 @@ void AP_InertialSensor::_start_backends() for (uint8_t i = 0; i < _backend_count; i++) { _backends[i]->start(); + if (_gyro_count == INS_MAX_INSTANCES && + _accel_count == INS_MAX_INSTANCES) { + // this can happen with UAVCAN backends and 3 SPI IMUs + break; + } } if (_gyro_count == 0 || _accel_count == 0) { @@ -733,6 +739,11 @@ AP_InertialSensor::detect_backends(void) ADD_BACKEND(AP_InertialSensor_HIL::detect(*this)); return; } + +#if HAL_WITH_UAVCAN + ADD_BACKEND(AP_InertialSensor_UAVCAN::probe(*this)); +#endif + #if defined(HAL_INS_PROBE_LIST) // IMUs defined by IMU lines in hwdef.dat HAL_INS_PROBE_LIST; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.cpp new file mode 100644 index 0000000000..c9f23f4170 --- /dev/null +++ b/libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.cpp @@ -0,0 +1,172 @@ +#include + +#if HAL_WITH_UAVCAN + +#include "AP_InertialSensor_UAVCAN.h" + +#include +#include + +#include + +extern const AP_HAL::HAL& hal; + +#define BACKEND_SAMPLE_RATE 2000 + +// UAVCAN Frontend Registry Binder +UC_REGISTRY_BINDER(FastIMUCb, ardupilot::imu::FastIMU); + +AP_InertialSensor_UAVCAN::DetectedModules AP_InertialSensor_UAVCAN::_detected_modules[] = {0}; + +HAL_Semaphore AP_InertialSensor_UAVCAN::_sem_registry; + +/* + constructor + */ +AP_InertialSensor_UAVCAN::AP_InertialSensor_UAVCAN(AP_InertialSensor &ins) : + AP_InertialSensor_Backend(ins) +{} + +/* + subscribe to UAVCAN messages, called in AP_UAVCAN startup + */ +void AP_InertialSensor_UAVCAN::subscribe_msgs(AP_UAVCAN* ap_uavcan) +{ + if (ap_uavcan == nullptr) { + return; + } + + auto *node = ap_uavcan->get_node(); + + uavcan::Subscriber *FastIMU_listener; + FastIMU_listener = new uavcan::Subscriber(*node); + + // Msg Handler + const int FastIMU_listener_res = FastIMU_listener->start(FastIMUCb(ap_uavcan, &handle_FastIMU)); + if (FastIMU_listener_res < 0) { + AP_HAL::panic("UAVCAN InertialSensor subscriber start fail"); + return; + } +} + +AP_InertialSensor_Backend* AP_InertialSensor_UAVCAN::probe(AP_InertialSensor &ins) +{ + WITH_SEMAPHORE(_sem_registry); + + AP_InertialSensor_UAVCAN* backend = nullptr; + for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) { + if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_uavcan != nullptr) { + backend = new AP_InertialSensor_UAVCAN(ins); + if (backend) { + _detected_modules[i].driver = backend; + backend->_ap_uavcan = _detected_modules[i].ap_uavcan; + backend->_node_id = _detected_modules[i].node_id; + } + break; + } + } + return backend; +} + +/* + find a matching backend for a node_id + */ +AP_InertialSensor_UAVCAN* AP_InertialSensor_UAVCAN::get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new) +{ + if (ap_uavcan == nullptr) { + return nullptr; + } + for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) { + if (_detected_modules[i].driver != nullptr && + _detected_modules[i].ap_uavcan == ap_uavcan && + _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 < INS_MAX_INSTANCES; i++) { + if (_detected_modules[i].ap_uavcan == ap_uavcan && _detected_modules[i].node_id == node_id) { + already_detected = true; + break; + } + } + if (!already_detected) { + for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) { + if (_detected_modules[i].ap_uavcan == nullptr) { + _detected_modules[i].ap_uavcan = ap_uavcan; + _detected_modules[i].node_id = node_id; + break; + } + } + } + } + + return nullptr; +} + +/* + handler for incoming FastIMU messages + */ +void AP_InertialSensor_UAVCAN::handle_FastIMU(AP_UAVCAN* ap_uavcan, uint8_t node_id, const FastIMUCb &cb) +{ + AP_InertialSensor_UAVCAN* driver; + { + WITH_SEMAPHORE(_sem_registry); + driver = get_uavcan_backend(ap_uavcan, node_id, true); + if (driver == nullptr) { + return; + } + } + { + auto *msg = cb.msg; + static uint8_t last_counter; + if ((last_counter+1) % 256 != msg->counter) { + ::printf("FastIMU lost %u %u\n", last_counter, msg->counter); + } + last_counter = msg->counter; + + Vector3f accel(msg->accel[0], msg->accel[1], msg->accel[2]); + accel *= (10.0 * (1+msg->accel_scale)) / INT16_MAX; + + Vector3f gyro(msg->gyro[0], msg->gyro[1], msg->gyro[2]); + gyro *= float(1+msg->gyro_scale) / INT16_MAX; + + WITH_SEMAPHORE(driver->_sem); + driver->sample_time_us = msg->time_us; + + driver->_rotate_and_correct_accel(driver->accel_instance, accel); + driver->_notify_new_accel_raw_sample(driver->accel_instance, accel); + + driver->_rotate_and_correct_gyro(driver->gyro_instance, gyro); + driver->_notify_new_gyro_raw_sample(driver->gyro_instance, gyro); + } +} + +// Read the sensor +bool AP_InertialSensor_UAVCAN::update(void) +{ + WITH_SEMAPHORE(_sem); + update_accel(accel_instance); + update_gyro(gyro_instance); + return true; +} + +void AP_InertialSensor_UAVCAN::start() +{ + if (sample_time_us != 0) { + uint32_t devid = AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN, + _ap_uavcan->get_driver_index(), + _node_id, + 0); + ::printf("registering UAVCAN IMU for %u\n", _node_id); + accel_instance = _imu.register_accel(1e6/sample_time_us, devid); + gyro_instance = _imu.register_gyro(1e6/sample_time_us, devid); + } +} + + +#endif // HAL_WITH_UAVCAN + diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.h b/libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.h new file mode 100644 index 0000000000..2ce4d27a4e --- /dev/null +++ b/libraries/AP_InertialSensor/AP_InertialSensor_UAVCAN.h @@ -0,0 +1,57 @@ +/* + * 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 . + */ +/* + support for UAVCAN IMUs using the ardupilot::imu::FastIMU message + */ +#pragma once + +#include + +#include "AP_InertialSensor.h" +#include "AP_InertialSensor_Backend.h" +#include + +class FastIMUCb; + +class AP_InertialSensor_UAVCAN : public AP_InertialSensor_Backend { +public: + void start() override; + bool update() override; + + static void subscribe_msgs(AP_UAVCAN* ap_uavcan); + static AP_InertialSensor_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id, bool create_new); + static AP_InertialSensor_Backend* probe(AP_InertialSensor &ins); + + static void handle_FastIMU(AP_UAVCAN* ap_uavcan, uint8_t node_id, const FastIMUCb &cb); + +private: + AP_InertialSensor_UAVCAN(AP_InertialSensor &imu); + + AP_UAVCAN* _ap_uavcan; + uint8_t _node_id; + uint16_t sample_time_us; + + // Module Detection Registry + static struct DetectedModules { + AP_UAVCAN *ap_uavcan; + uint8_t node_id; + AP_InertialSensor_UAVCAN *driver; + } _detected_modules[INS_MAX_INSTANCES]; + + static HAL_Semaphore _sem_registry; + + uint8_t accel_instance; + uint8_t gyro_instance; +}; From 147fbf2d227626db4017e13484ef73768607b7fc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Jul 2020 18:10:03 +1000 Subject: [PATCH 155/155] AP_UAVCAN: fixed dsdl ID conflict --- .../equipment/gnss/{20002.Inject.uavcan => 20003.Inject.uavcan} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/{20002.Inject.uavcan => 20003.Inject.uavcan} (100%) diff --git a/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan b/libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20003.Inject.uavcan similarity index 100% rename from libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20002.Inject.uavcan rename to libraries/AP_UAVCAN/dsdl/ardupilot/equipment/gnss/20003.Inject.uavcan