diff --git a/AntennaTracker/ReleaseNotes.txt b/AntennaTracker/ReleaseNotes.txt index bb406e3cf176f..82af087808300 100644 --- a/AntennaTracker/ReleaseNotes.txt +++ b/AntennaTracker/ReleaseNotes.txt @@ -1,4 +1,68 @@ Antenna Tracker Release Notes: +------------------------------ +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) ------------------------------------------------------------------ Release 4.5.1 8th April 2024 @@ -11,25 +75,9 @@ be affected by the bug, so this was just a precaution. There are no other changes in this release. ------------------------------------------------------------------ -Release 4.5.0-beta4 22nd March 2024 - -Changes from 4.5.0-beta3 - -1) system changes - -- fixed a cache corruption issue with microSD card data on H7 based boards -- rename parameter NET_ENABLED to NET_ENABLE -- fixed FDCAN labels for adding new H7 boards -- avoid logging dma.txt to save CPU -- fixed roll/pitch in viewpro driver -- added band X in VideoTX -- fixed quaternion attitude reporting for Microstrain external AHRS -- add RPLidarC1 proximity support - -2) new boards -- added MicoAir405v2 -- add Orqa F405 Pro +Release 4.5.0 2nd April 2024 +No changes from 4.5.0-beta4 ------------------------------------------------------------------ Release 4.5.0 2nd April 2024 diff --git a/AntennaTracker/version.h b/AntennaTracker/version.h index 64465f9ce51d7..0166278c74151 100644 --- a/AntennaTracker/version.h +++ b/AntennaTracker/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "AntennaTracker V4.5.1" +#define THISFIRMWARE "AntennaTracker V4.5.3" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,5,1,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 4 #define FW_MINOR 5 -#define FW_PATCH 1 +#define FW_PATCH 3 #define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL #include diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index faf5e4df70a75..a2d00ccb3a872 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,5 +1,80 @@ ArduPilot Copter Release Notes: ------------------------------- +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +3) Copter specific changes + +- fixed speed constraint during avoidance backoff +- zero D_FF during autotune twitch + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Copter specific changes + +- Auto mode condition yaw fix to avoid pointing at out-of-date target +- Guided mode angle control yaw target initialisation fix (was always turning North) + +5) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) + +------------------------------------------------------------------ Release 4.5.1 8th April 2024 diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index ba9a52f60ed26..9f8c0cf2bd511 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -313,14 +313,11 @@ void ModeGuided::angle_control_start() // initialise targets guided_angle_state.update_time_ms = millis(); - guided_angle_state.attitude_quat.initialise(); + guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z)); guided_angle_state.ang_vel.zero(); guided_angle_state.climb_rate_cms = 0.0f; guided_angle_state.yaw_rate_cds = 0.0f; guided_angle_state.use_yaw_rate = false; - - // pilot always controls yaw - auto_yaw.set_mode(AutoYaw::Mode::HOLD); } // set_destination - sets guided mode's target destination @@ -939,7 +936,7 @@ void ModeGuided::angle_control_run() // check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds uint32_t tnow = millis(); if (tnow - guided_angle_state.update_time_ms > get_timeout_ms()) { - guided_angle_state.attitude_quat.initialise(); + guided_angle_state.attitude_quat.from_euler(Vector3f(0.0, 0.0, attitude_control->get_att_target_euler_rad().z)); guided_angle_state.ang_vel.zero(); climb_rate_cms = 0.0f; if (guided_angle_state.use_thrust) { diff --git a/ArduCopter/version.h b/ArduCopter/version.h index b8c02702e824d..20296aeacd2ac 100644 --- a/ArduCopter/version.h +++ b/ArduCopter/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduCopter V4.5.1" +#define THISFIRMWARE "ArduCopter V4.5.3" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,5,1,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 4 #define FW_MINOR 5 -#define FW_PATCH 1 +#define FW_PATCH 3 #define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL #include diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index be3c63a40c730..656ea0b78eb65 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -533,7 +533,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: PTCH_LIM_MIN_DEG // @DisplayName: Minimum Pitch Angle // @Description: Maximum pitch down angle commanded in modes with stabilized limits - // @Units: cdeg + // @Units: deg // @Range: -90 0 // @Increment: 10 // @User: Standard diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index a510dd83db0b7..f30543a712d2f 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,6 +1,6 @@ -Release 4.5.1.1 8th April 2024 +Release 4.5.3.1 8th April 2024 ------------------------------------- -Changes from stock 4.5.1: +Changes from stock 4.5.3: 1) Safety patches - Failsafe during auto takeoff switches to QLand #26260 @@ -14,6 +14,82 @@ Changes from stock 4.5.1: 3) Scripts (no impact on firmware) - Created Engine-Out automatic failsafe script and associated tests +ArduPilot Plane Release Notes: +------------------------------ +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +3) Plane specific changes + +- fixed cancelling of FWD_GAIN setting for tiltrotors + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Plane specific changes + +- Drop min Q_TRANSITION_MS to 500ms +- FBWB/CRUISE missing zero crossing of elevator input fix +- PTCH_LIM_MIN_DEG param units fixed to be deg + +5) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) + Release 4.5.1 8th April 2024 ---------------------------- diff --git a/ArduPlane/mode_rtl.cpp b/ArduPlane/mode_rtl.cpp index ee851089e2087..ae0283c98ae17 100644 --- a/ArduPlane/mode_rtl.cpp +++ b/ArduPlane/mode_rtl.cpp @@ -95,6 +95,13 @@ void ModeRTL::navigate() } #endif + uint16_t radius = abs(plane.g.rtl_radius); + if (radius > 0) { + plane.loiter.direction = (plane.g.rtl_radius < 0) ? -1 : 1; + } + + plane.update_loiter(radius); + if (!plane.auto_state.checked_for_autoland) { if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) || (plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START && @@ -116,13 +123,6 @@ void ModeRTL::navigate() plane.auto_state.checked_for_autoland = true; } } - - uint16_t radius = abs(plane.g.rtl_radius); - if (radius > 0) { - plane.loiter.direction = (plane.g.rtl_radius < 0) ? -1 : 1; - } - - plane.update_loiter(radius); } #if HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 762b190ffee72..3abf8a58becef 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -394,15 +394,16 @@ void Plane::update_fbwb_speed_height(void) elevator_input = -elevator_input; } - int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100; - change_target_altitude(alt_change_cm); - - if (is_zero(elevator_input) && !is_zero(target_altitude.last_elevator_input)) { - // the user has just released the elevator, lock in - // the current altitude + bool input_stop_climb = !is_positive(elevator_input) && is_positive(target_altitude.last_elevator_input); + bool input_stop_descent = !is_negative(elevator_input) && is_negative(target_altitude.last_elevator_input); + if (input_stop_climb || input_stop_descent) { + // user elevator input reached or passed zero, lock in the current altitude set_target_altitude_current(); } + int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100; + change_target_altitude(alt_change_cm); + #if HAL_SOARING_ENABLED if (g2.soaring_controller.is_active()) { if (g2.soaring_controller.get_throttle_suppressed()) { diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 524a2006b7642..387ff68699c5c 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -33,7 +33,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @DisplayName: Transition time // @Description: Transition time in milliseconds after minimum airspeed is reached // @Units: ms - // @Range: 2000 30000 + // @Range: 500 30000 // @User: Advanced AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000), @@ -1714,7 +1714,7 @@ void SLT_Transition::update() // after airspeed is reached we degrade throttle over the // transition time, but continue to stabilize const uint32_t transition_timer_ms = now - transition_low_airspeed_ms; - const float trans_time_ms = constrain_float(quadplane.transition_time_ms,2000,30000); + const float trans_time_ms = constrain_float(quadplane.transition_time_ms,500,30000); if (transition_timer_ms > unsigned(trans_time_ms)) { transition_state = TRANSITION_DONE; in_forced_transition = false; diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 0be2a07845282..50132a2a15d8c 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -295,7 +295,7 @@ void Tiltrotor::continuous_update(void) // operate in all VTOL modes except Q_AUTOTUNE. Forward rotor tilt is used to produce // forward thrust equivalent to what would have been produced by a forward thrust motor // set to quadplane.forward_throttle_pct() - const float fwd_g_demand = 0.01f * quadplane.forward_throttle_pct() / plane.quadplane.q_fwd_thr_gain; + const float fwd_g_demand = 0.01 * quadplane.forward_throttle_pct(); const float fwd_tilt_deg = MIN(degrees(atanf(fwd_g_demand)), (float)max_angle_deg); slew(MIN(fwd_tilt_deg * (1/90.0), get_forward_flight_tilt())); return; diff --git a/ArduPlane/version.h b/ArduPlane/version.h index 607261c61db93..b858064e3359a 100644 --- a/ArduPlane/version.h +++ b/ArduPlane/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduPlane V4.5.1.1" +#define THISFIRMWARE "ArduPlane V4.5.3.1" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,5,1,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 4 #define FW_MINOR 5 -#define FW_PATCH 1 +#define FW_PATCH 3 #define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL #include diff --git a/Rover/release-notes.txt b/Rover/ReleaseNotes.txt similarity index 98% rename from Rover/release-notes.txt rename to Rover/ReleaseNotes.txt index 940bcb44de0d1..6a4620cf93770 100644 --- a/Rover/release-notes.txt +++ b/Rover/ReleaseNotes.txt @@ -1,5 +1,74 @@ Rover Release Notes: -------------------- +Release 4.5.3 28th May 2024 + +No changes from 4.5.3-beta1 +------------------------------------------------------------------ +Release 4.5.3-beta1 16th May 2024 + +Changes from 4.5.2 + +1) Board specific enhancements and bug fixes + +- correct default GPS port on MambaH743v4 +- added SDMODELV2 +- added iFlight Blitz H7 Pro +- added BLITZ Wing H743 +- added highres IMU sampling on Pixhawk6X + +2) System level minor enhancements and bug fixes + +- fixed rare crash bug in lua scripting on script fault handling +- fixed Neopixel pulse proportions to work with more LED variants +- fixed timeout in lua rangefinder drivers +- workaround hardware issue in IST8310 compass +- allow FIFO rate logging for highres IMU sampling + +3) Rover specific changes + +- correct clamping of RTL_SPEED for fractional speed values + +------------------------------------------------------------------ +Release 4.5.2 14th May 2024 + +No changes from 4.5.2-beta1 +------------------------------------------------------------------ +Release 4.5.2-beta1 29th April 2024 + +Changes from 4.5.1 + +1) Board specific enhancements and bug fixes + +- FoxeerF405v2 support +- iFlight BLITZ Mini F745 support +- Pixhawk5X, Pixhawk6C, Pixhawk6X, Durandal power peripherals immediately at startup + +2) System level minor enhancements and bug fixes + +- Camera lens (e.g. RGB, IR) can be selected from GCS or during missions using set-camera-source +- Crashdump pre-arm check added +- Gimbal gets improved yaw lock reporting to GCS +- Gimbal default mode fixed (MNTx_DEFLT_MODE was being overriden by RC input) +- RM3100 compass SPI bus speed reduced to 1Mhz +- SBUS output fix for channels 1 to 8 also applying to 9 to 16 +- ViewPro gimbal supports enable/disable rangefinder from RC aux switch +- Visual Odometry delay fixed (was always using 1ms delay, see VISO_DELAY_MS) +- fixed serial passthrough to avoid data loss at high data rates + +3) AHRS / EKF fixes + +- Compass learning disabled when using GPS-for-yaw +- GSF reset minimum speed reduced to 1m/s (except Plane which remains 5m/s) +- MicroStrain7 External AHRS position quantization bug fix +- MicroStrain7 init failure warning added +- MicroStrain5 and 7 position and velocity variance reporting fix + +4) Other minor enhancements and bug fixes + +- DDS_UDP_PORT parameter renamed (was DDS_PORT) +- Harmonic Notch bitmask parameter conversion fix (see INS_HNTCH_HMNCS) + +------------------------------------------------------------------ Release 4.5.1 8th April 2024 This release fixes a critical bug in the CRSF R/C protocol parser that diff --git a/Rover/mode_rtl.cpp b/Rover/mode_rtl.cpp index e896c5151fc87..8fe2ad75959d7 100644 --- a/Rover/mode_rtl.cpp +++ b/Rover/mode_rtl.cpp @@ -8,7 +8,7 @@ bool ModeRTL::_enter() } // initialise waypoint navigation library - g2.wp_nav.init(MAX(0, g2.rtl_speed)); + g2.wp_nav.init(MAX(0.0f, g2.rtl_speed)); // set target to the closest rally point or home #if HAL_RALLY_ENABLED diff --git a/Rover/version.h b/Rover/version.h index 4c2dcbc665e1b..7cb0fee45b882 100644 --- a/Rover/version.h +++ b/Rover/version.h @@ -6,14 +6,14 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduRover V4.5.1" +#define THISFIRMWARE "ArduRover V4.5.3" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,5,1,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 4,5,3,FIRMWARE_VERSION_TYPE_OFFICIAL #define FW_MAJOR 4 #define FW_MINOR 5 -#define FW_PATCH 1 +#define FW_PATCH 3 #define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL #include diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index e604b12beb4c5..1348e0926ebf7 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -65,11 +65,11 @@ Reserved "NXP ucans32k146" 34 # values from external vendors EXT_HW_RADIOLINK_MINI_PIX 3 -# NOTE: the full range from 1000 to 1999 (inclusive) is reserved for +# NOTE: the full range from 1000 to 19999 (inclusive) is reserved for # use by the ArduPilot bootloader. Do not allocate IDs in this range # except via changes to the ArduPilot code -# Do not allocate IDs in the range 1000 to 1999 except via a PR +# Do not allocate IDs in the range 1000 to 19999 except via a PR # against this file in https://github.com/ArduPilot/ardupilot/tree/master/Tools/AP_Bootloader/board_types.txt # values starting with AP_ are implemented in the ArduPilot bootloader @@ -227,7 +227,7 @@ AP_HW_YJUAV_A6 1113 AP_HW_YJUAV_A6Nano 1114 AP_HW_ACNS_CM4PILOT 1115 AP_HW_ACNS_F405AIO 1116 -AP_HW_BLITZF7 1117 +AP_HW_BLITZF7AIO 1117 AP_HW_RADIX2HD 1118 AP_HW_HEEWING_F405 1119 AP_HW_PodmanH7 1120 @@ -264,6 +264,21 @@ AP_HW_BotBloxSwitch 1148 AP_HW_MatekH7A3 1149 AP_HW_MicoAir405v2 1150 AP_HW_ORAQF405PRO 1155 +AP_HW_CBU_StampH743 1156 +AP_HW_FOXEERF405_V2 1157 +AP_HW_CSKY405 1158 +AP_HW_NxtPX4v2 1159 +AP_HW_PixPilot-V6PRO 1160 +AP_HW_MicoAir405Mini 1161 +AP_HW_BlitzH7Pro 1162 +AP_HW_BlitzF7Mini 1163 +AP_HW_BlitzF7 1164 +AP_HW_MicoAir743 1166 +AP_HW_BlitzH7Wing 1168 +AP_HW_SDMODELH7V2 1167 + +AP_HW_JHEMCUF405WING 1169 +AP_HW_MatekG474 1170 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 @@ -280,7 +295,15 @@ AP_HW_VIMDRONES_PERIPH 1407 AP_HW_PIXHAWK6X_PERIPH 1408 AP_HW_CUBERED_PERIPH 1409 +AP_HW_RadiolinkPIX6 1410 + +AP_HW_JHEMCU-H743HD 1411 + +AP_HW_LongbowF405 1422 + +AP_HW_MountainEagleH743 1444 +AP_HW_SakuraRC-H743 2714 # IDs 5000-5099 reserved for Carbonix # IDs 5100-5199 reserved for SYPAQ Systems @@ -302,8 +325,22 @@ AP_HW_Sierra-TrueFlow 5307 AP_HW_Sierra-TrueNavIC-Pro 5308 AP_HW_Sierra-F1-Pro 5309 +#IDs 5401-5499 reserved for holybro +AP_HW_Holybro-PMU-F4 5401 +AP_HW_Holybro-UM982-G4 5402 +AP_HW_Holybro-UM960-H7 5403 +AP_HW_Holybro-PERIPH-H7 5404 + +#IDs 5501-5599 reserved for MATEKSYS +AP_HW_MATEKH743SE 5501 + # IDs 6000-6099 reserved for SpektreWorks +# IDs 6600-6699 reserved for Eagle Eye Drones + # OpenDroneID enabled boards. Use 10000 + the base board ID AP_HW_CubeOrange_ODID 10140 AP_HW_Pixhawk6_ODID 10053 + +# do not allocate board IDs above 10,000 for non-ODID boards. +# do not allocate board IDs above 19,999 in this file. diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin index 5934290788ad0..77063c20a1725 100755 Binary files a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin and b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin index c65751281d15a..a6ccc264c2f90 100755 Binary files a/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin index adbf98f090cde..cab9f0f1a8b00 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin index fce01bb26c29e..53d8c78ec4615 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin index 2ba418de0788f..4c87d413764b7 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin index 1a0426c5761b6..5ce245d0e0400 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_highpolh.bin index af9d068cd5ea5..a63692a92ea54 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_highpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin index 8db3cfaad172d..b22b1c553c52a 100755 Binary files a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_highpolh.bin b/Tools/IO_Firmware/iofirmware_highpolh.bin index 988375fa5d73c..712d65559ee78 100755 Binary files a/Tools/IO_Firmware/iofirmware_highpolh.bin and b/Tools/IO_Firmware/iofirmware_highpolh.bin differ diff --git a/Tools/IO_Firmware/iofirmware_lowpolh.bin b/Tools/IO_Firmware/iofirmware_lowpolh.bin index 059048670ef3f..4a185d958c957 100755 Binary files a/Tools/IO_Firmware/iofirmware_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_lowpolh.bin differ diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 9e397c3af8ac4..dd044e36a0e99 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1602,6 +1602,58 @@ def MaxAltFence(self): self.zero_throttle() + # MaxAltFence - fly up and make sure fence action does not trigger + # Also check that the vehicle will not try and descend too fast when trying to backup from a max alt fence due to avoidance + def MaxAltFenceAvoid(self): + '''Test Max Alt Fence Avoidance''' + self.takeoff(10, mode="LOITER") + """Hold loiter position.""" + + # enable fence, only max altitude, defualt is 100m + # No action, rely on avoidance to prevent the breach + self.set_parameters({ + "FENCE_ENABLE": 1, + "FENCE_TYPE": 1, + "FENCE_ACTION": 0, + }) + + # Try and fly past the fence + self.set_rc(3, 1920) + + # Avoid should prevent the vehicle flying past the fence, so the altitude wait should timeouts + try: + self.wait_altitude(140, 150, timeout=90, relative=True) + raise NotAchievedException("Avoid should prevent reaching altitude") + except AutoTestTimeoutException: + pass + except Exception as e: + raise e + + # Check descent is not too fast, allow 10% above the configured backup speed + max_descent_rate = -self.get_parameter("AVOID_BACKUP_SPD") * 1.1 + + def get_climb_rate(mav, m): + m_type = m.get_type() + if m_type != 'VFR_HUD': + return + if m.climb < max_descent_rate: + raise NotAchievedException("Decending too fast want %f got %f" % (max_descent_rate, m.climb)) + + self.context_push() + self.install_message_hook_context(get_climb_rate) + + # Reduce fence alt, this will result in a fence breach, but there is no action. + # Avoid should then backup the vehicle to be under the new fence alt. + self.set_parameters({ + "FENCE_ALT_MAX": 50, + }) + self.wait_altitude(40, 50, timeout=90, relative=True) + + self.context_pop() + + self.set_rc(3, 1500) + self.do_RTL() + # fly_alt_min_fence_test - fly down until you hit the fence floor def MinAltFence(self): '''Test Min Alt Fence''' @@ -10124,6 +10176,7 @@ def tests1d(self): self.HorizontalFence, self.HorizontalAvoidFence, self.MaxAltFence, + self.MaxAltFenceAvoid, self.MinAltFence, self.FenceFloorEnabledLanding, self.AutoTuneSwitch, diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 12b7cfda70db0..8cd4bc80826a2 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -1662,6 +1662,115 @@ def DCMClimbRate(self): # Force disarm self.disarm_vehicle(force=True) + def RTL_AUTOLAND_1(self): + '''test behaviour when RTL_AUTOLAND==1''' + + self.set_parameters({ + "RTL_AUTOLAND": 1, + }) + + # when RTL is entered and RTL_AUTOLAND is 1 we should fly home + # then to the landing sequence. This mission puts the landing + # sequence well to the West of home so if we go directly there + # we won't come within 200m of home + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + # fly North + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30), + # add a waypoint 1km North (which we will look for and trigger RTL + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30), + + # *exciting* landing sequence is ~1km West and points away from Home. + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_LAND_START, + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5), + (mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0), + ]) + self.check_mission_upload_download(wps) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + self.wait_current_waypoint(3) # will be 2km North here + self.change_mode('RTL') + + self.wait_distance_to_home(100, 200, timeout=120) + self.wait_current_waypoint(7) + + self.fly_home_land_and_disarm() + + def send_reposition_to_loc(self, loc): + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_REPOSITION, + 0, + 1, # reposition flags; 1 means "change to guided" + 0, + 0, + int(loc.lat * 1e7), + int(loc.lng * 1e7), + 20, # alt + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + ) + + def reposition_to_loc(self, loc, accuracy=100): + self.send_reposition_to_loc(loc) + self.wait_location( + loc, + accuracy=accuracy, + minimum_duration=20, + timeout=120, + ) + + def RTL_AUTOLAND_1_FROM_GUIDED(self): + '''test behaviour when RTL_AUTOLAND==1 and entering from guided''' + + self.set_parameters({ + "RTL_AUTOLAND": 1, + }) + + # when RTL is entered and RTL_AUTOLAND is 1 we should fly home + # then to the landing sequence. This mission puts the landing + # sequence well to the West of home so if we go directly there + # we won't come within 200m of home + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + # fly North + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, 30), + # add a waypoint 1km North (which we will look for and trigger RTL + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 30), + + # *exciting* landing sequence is ~1km West and points away from Home. + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_LAND_START, + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1000, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1300, 15), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, -1600, 5), + (mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND, 0, -1750, 0), + ]) + self.check_mission_upload_download(wps) + self.set_current_waypoint(0, check_afterwards=False) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + here = self.mav.location() + guided_loc = self.offset_location_ne(here, 500, -500) + + self.arm_vehicle() + self.wait_current_waypoint(3) # will be 2km North here + self.reposition_to_loc(guided_loc) + self.send_cmd_do_set_mode('RTL') + + self.wait_distance_to_home(100, 200, timeout=120) + self.wait_current_waypoint(7) + + self.fly_home_land_and_disarm() + def tests(self): '''return list of all tests''' @@ -1706,5 +1815,7 @@ def tests(self): self.MAV_CMD_NAV_TAKEOFF, self.Q_GUIDED_MODE, self.DCMClimbRate, + self.RTL_AUTOLAND_1, # as in fly-home then go to landing sequence + self.RTL_AUTOLAND_1_FROM_GUIDED, # as in fly-home then go to landing sequence ]) return ret diff --git a/Tools/bootloaders/BlitzF745_bl.bin b/Tools/bootloaders/BlitzF745_bl.bin new file mode 100644 index 0000000000000..750ade6946435 Binary files /dev/null and b/Tools/bootloaders/BlitzF745_bl.bin differ diff --git a/Tools/bootloaders/BlitzF745_bl.hex b/Tools/bootloaders/BlitzF745_bl.hex new file mode 100644 index 0000000000000..9ab87d321e97e --- /dev/null +++ b/Tools/bootloaders/BlitzF745_bl.hex @@ -0,0 +1,929 @@ +:020000040800F2 +:1000000000060120010200080302000803020008A4 +:1000100003020008030200080302000803020008AC +:1000200003020008030200080302000899310008D7 +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:100050000302000803020008413400086934000864 +:1000600091340008B9340008E134000803020008A4 +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:1000900003020008030200080302000809350008F3 +:1000A000030200080302000803020008030200081C +:1000B000DD350008030200080302000803020008FF +:1000C00003020008030200080302000803020008FC +:1000D00003020008030200080302000803020008EC +:1000E0006D3500080302000803020008030200083F +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:100140000302000803020008030200080D2900084A +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:10018000030200080302000803020008030200083B +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F01F0A8FFA9 +:1002700002F024FF4FF055301F491B4A91423CBF0A +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE701F0C0FF02F05EFF1B +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E701F0A8BF00060120002201209D +:1002F0000000000808ED00E00000012000060120D9 +:1003000090390008002201205C2201206022012097 +:10031000882E0120000200080002000800020008E8 +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F0E4FAFEE701F0FA +:100350006DFA00DFFEE7000038B500F011FC01F097 +:10036000EFFE054601F022FF0446C8B90E4B9D4240 +:1003700018D001339D4218BF044641F2883504BFAE +:1003800001240025002001F0E5FE0CB100F076F814 +:1003900000F05EFD284600F0FDF800F06FF8F9E788 +:1003A0000025EFE70546EDE7010007B008B500F0CE +:1003B000B9FBA0F120035842584108BD07B541F2EE +:1003C0001203022101A8ADF8043000F0C9FB03B00C +:1003D0005DF804FB38B572B6302383F3118862B63A +:1003E000174803680BB101F063FB164A1448002359 +:1003F0004FF47A7101F052FB002383F31188124C01 +:10040000236813B12368013B2360636813B16368F9 +:10041000013B63600D4D2B7833B963687BB90220D3 +:1004200000F080FC322363602B78032B07D16368D4 +:100430002BB9022000F076FC4FF47A73636038BD6C +:1004400060220120D50300088023012078220120AA +:10045000084B187003280CD8DFE800F008050208E4 +:10046000022000F055BC022000F048BC024B0022E4 +:100470005A6070477822012080230120F8B5404B54 +:10048000404A1C461968013179D004339342F9D1AE +:100490006268A24273D33C4B9B6803F1006303F58F +:1004A000C0339A426BD2002000F084FB0220FFF799 +:1004B000CFFF364B00211A6C19641A6E19661A6E3A +:1004C0005A6C59645A6E59665A6E5A6942F08002E3 +:1004D0005A615A6922F080025A615A691A6942F0D7 +:1004E00000521A611A6922F000521A611B6972B631 +:1004F0004FF0E023C3F8084DD4E90004BFF34F8F59 +:10050000BFF36F8F224AC2F88410BFF34F8F536935 +:1005100023F480335361BFF34F8FD2F88030C3F39D +:10052000C905C3F34E335B0143F6E07603EA060CDC +:1005300029464CEA81770139C2F87472F9D2203B1E +:1005400013F1200FF2D1BFF34F8FBFF36F8FBFF3C3 +:100550004F8FBFF36F8F536923F400335361002330 +:10056000C2F85032BFF34F8FBFF36F8F72B6302394 +:1005700083F3118862B6854680F308882047F8BD6A +:10058000008001082080010800220120003802407C +:1005900000ED00E02DE9F04F93B0B64B0090202223 +:1005A000FF210AA89D6800F0FDFBB34A1378B3B998 +:1005B000B24801211170036072B6302383F31188B1 +:1005C00062B603680BB101F073FAAD4AAB48002381 +:1005D0004FF47A7101F062FA002383F31188009BD3 +:1005E00013B1A84B009A1A60A74A009C1378032BFA +:1005F0001EBF00231370A34A4FF0000A18BF5360B8 +:10060000D3465646D146012000F082FB24B19D4BD3 +:100610001B68002B00F02782002000F083FA039073 +:10062000039B002BF2DB012000F068FB039B213BC6 +:100630001F2BE8D801A252F823F000BFBD06000826 +:10064000E506000879070008070600080706000805 +:10065000070600080B080008DB090008F508000879 +:10066000570900087F090008A509000807060008C7 +:10067000B709000807060008290A00085D070008F6 +:10068000070600086D0A0008C90600085D07000893 +:1006900007060008570900080706000807060008B3 +:1006A00007060008070600080706000807060008F6 +:1006B0000706000807060008790700080220FFF770 +:1006C00075FE002840F0F981009B0221BAF1000F6D +:1006D00008BF1C4605A841F21233ADF8143000F0F3 +:1006E0003FFA90E74FF47A7000F01CFA071EEBDB3C +:1006F0000220FFF75BFE0028E6D0013F052F00F245 +:10070000DE81DFE807F0030A0D1013360523059399 +:10071000042105A800F024FA17E056480421F9E75F +:100720005A480421F6E75A480421F3E74FF01C0821 +:10073000404600F041FA08F104080590042105A89C +:1007400000F00EFAB8F12C0FF2D1012000FA07F7F1 +:1007500047EA0B0B5FFA8BFB4FF0000900F06EFBD2 +:1007600026B10BF00B030B2B08BF0024FFF726FE6E +:1007700049E748480421CDE7002EA5D00BF00B0334 +:100780000B2BA1D10220FFF711FE074600289BD0BA +:10079000012000F00FFA0220FFF75AFE00261FFA90 +:1007A00086F8404600F016FA0446B0B10399A1F16C +:1007B000400251425141404600F01CFA01360028E7 +:1007C000EDD1BA46044641F21213022105A8ADF854 +:1007D00014303E4600F0C4F915E70120FFF738FE5B +:1007E0002546244B9B68AB4207D9284600F0E4F924 +:1007F000013040F067810435F3E7234B00251D707D +:10080000204BBA465D603E46A8E7002E3FF45CAF41 +:100810000BF00B030B2B7FF457AF0220FFF718FEF2 +:10082000322000F07FF9B0F10008FFF64DAF18F06C +:1008300003077FF449AF0F4A926808EB0503934220 +:100840003FF642AFB8F5807F3FF73EAF124B0193C2 +:10085000B84523DD4FF47A7000F064F90390039AF1 +:10086000002AFFF631AF019B039A03F8012B0137F1 +:10087000EDE700BF002201207C230120602201203F +:10088000D5030008802301207822012004220120C2 +:10089000082201200C2201207C220120C820FFF721 +:1008A00085FD074600283FF40FAF1F2D11D8C5F175 +:1008B000200242450AAB25F0030028BF4246834987 +:1008C0000192184400F048FA019A8048FF2100F094 +:1008D00069FA4FEAA8037D490193C8F387022846C5 +:1008E00000F068FA064600283FF46DAF019B05EB67 +:1008F000830533E70220FFF759FD00283FF4E4AEFB +:1009000000F0A4F900283FF4DFAE0027B846704B92 +:100910009B68BB4218D91F2F11D80A9B01330ED0F8 +:1009200027F0030312AA134453F8203C05934046D2 +:10093000042205A900F0B6FA04378046E7E73846F6 +:1009400000F03AF90590F2E7CDF81480042105A8EB +:1009500000F006F902E70023642104A8049300F0E4 +:10096000F5F800287FF4B0AE0220FFF71FFD002845 +:100970003FF4AAAE049800F051F90590E6E7002391 +:10098000642104A8049300F0E1F800287FF49CAEF1 +:100990000220FFF70BFD00283FF496AE049800F00C +:1009A0004DF9EAE70220FFF701FD00283FF48CAE85 +:1009B00000F05CF9E1E70220FFF7F8FC00283FF4C3 +:1009C00083AE05A9142000F057F9042107460490CE +:1009D00004A800F0C5F83946B9E7322000F0A2F8C3 +:1009E000071EFFF671AEBB077FF46EAE384A926801 +:1009F00007EB090393423FF667AE0220FFF7D6FCF0 +:100A000000283FF461AE27F003074F44B9453FF497 +:100A1000A5AE484600F0D0F80421059005A800F0E6 +:100A20009FF809F10409F1E74FF47A70FFF7BEFC73 +:100A300000283FF449AE00F009F9002844D00A9B91 +:100A400001330BD008220AA9002000F0B3F90028D6 +:100A50003AD02022FF210AA800F0A4F9FFF7AEFC4B +:100A60001C4800F05FFF13B0BDE8F08F002E3FF48C +:100A70002BAE0BF00B030B2B7FF426AE002364216F +:100A800005A8059300F062F8074600287FF41CAE25 +:100A90000220FFF78BFC804600283FF415AEFFF7DD +:100AA0008DFC41F2883000F03DFF059800F0F8F928 +:100AB000464600F0C3F93C46A5E506464EE64FF033 +:100AC000000901E6BA467EE637467CE67C22012034 +:100AD00000220120A086010070B50F4B1B78013366 +:100AE000DBB2012B0C4611D80C4D29684FF47A73F8 +:100AF0000E6AA2FB0332014622462846B0478442D2 +:100B000004D1074B00221A70012070BD4FF4FA7017 +:100B100000F008FF0020F8E710220120282601201D +:100B2000B423012007B50023024601210DF107007F +:100B30008DF80730FFF7D0FF20B19DF8070003B014 +:100B40005DF804FB4FF0FF30F9E700000A4608B5F6 +:100B50000421FFF7C1FF80F00100C0B2404208BD90 +:100B600030B4054C2368DD69044B0A46AC460146A7 +:100B7000204630BC604700BF28260120A086010027 +:100B800070B501F0E3F9094E094D30800024286862 +:100B90003388834208D901F0D3F92B680444013328 +:100BA000B4F5C03F2B60F2D370BD00BFB623012067 +:100BB0008823012001F078BA00F1006000F5C03010 +:100BC0000068704700F10060920000F5C03001F04D +:100BD00003BA0000054B1A68054B1B889B1A834219 +:100BE00002D9104401F0ACB90020704788230120DD +:100BF000B623012038B5084D044629B128682044A1 +:100C0000BDE8384001F0BCB92868204401F0A0F9E3 +:100C10000028F3D038BD00BF8823012010F0030363 +:100C200009D1B0F5846F04D200F10050A0F5712015 +:100C30000368184670470023FBE7000000F10050EE +:100C4000A0F57120D0F8200470470000064991F803 +:100C5000243033B10023086A81F824300822FFF7DA +:100C6000B1BF0120704700BF8C230120014B1868E1 +:100C7000704700BF002004E0F0B51E4B1D6801382E +:100C80002E0C0A181C48C5F30B04032335460788AD +:100C9000A7420BD144680B46013C934218461BD235 +:100CA00014F9010F48B103F8010BF6E7013B00F11D +:100CB0000800ECD191420ED20B4618462C24B6F512 +:100CC000805F00F8014B0AD1824202D94122981C70 +:100CD0005A70401AF0BD0846B6F5805FF9D041F26F +:100CE00001039D42F5D18242F3D95A2300F8013B1A +:100CF000EFE700BF002004E014220120022802BF19 +:100D0000024B4FF000729A61704700BF000802402A +:100D1000022802BF024B4FF400729A61704700BF75 +:100D200000080240022801BF024A536983F400739D +:100D3000536170470008024070B504464FF47A765C +:100D40004CB1412C254628BF412506FB05F000F09B +:100D5000E9FD641BF4E770BD10B50023934203D096 +:100D6000CC5CC4540133F9E710BD000010B5013864 +:100D700010F9013F3BB191F900409C4203D11AB1F7 +:100D80000131013AF4E71AB191F90020981A10BD27 +:100D90001046FCE703460246D01A12F9011B00294F +:100DA000FAD1704702440346934202D003F8011B74 +:100DB000FAE770472DE9F8431F4D144695F82420B3 +:100DC0000746884652BBDFF870909CB395F82430F4 +:100DD0002BB92022FF2148462F62FFF7E3FF95F849 +:100DE0002400C0F10802A24228BF2246D6B24146E2 +:100DF000920005EB8000FFF7AFFF95F82430A41BAD +:100E00001E44F6B2082E17449044E4B285F82460DC +:100E1000DBD1FFF71BFF0028D7D108E02B6A03EBDB +:100E200082038342CFD0FFF711FF0028CBD10020EF +:100E3000BDE8F8830120FBE78C230120024B1A78E0 +:100E4000024B1A70704700BFB4230120102201200A +:100E500010B5104C104800F0BBF821460E4800F0C9 +:100E6000E3F82468E26ED2F8043843F00203C2F8D3 +:100E700004384FF47A70FFF75FFF0849204600F00E +:100E8000E1F9E26ED2F8043823F00203C2F8043824 +:100E900010BD00BF58370008282601206037000821 +:100EA0007047000030B5094D0A4491420DD011F849 +:100EB000013B5840082340F30004013B2C4013F051 +:100EC000FF0384EA5000F6D1EFE730BD2083B8ED90 +:100ED00072B6302383F3118862B6704702684368A4 +:100EE0001143016003B118477047000013B5446B0C +:100EF000D4F894341A681178042915D1217C022978 +:100F000012D11979128901238B4013420CD101A906 +:100F100004F14C0001F090FFD4F89444019B217936 +:100F20000246206800F0DAF902B010BD143001F07A +:100F300015BF00004FF0FF33143001F00FBF000069 +:100F40004C3001F0E5BF00004FF0FF334C3001F0B2 +:100F5000DFBF0000143001F0E5BE00004FF0FF31AC +:100F6000143001F0DFBE00004C3001F0B1BF0000D2 +:100F70004FF0FF324C3001F0ABBF00000020704753 +:100F800010B5D0F894341A6811780429044617D1A2 +:100F9000017C022914D15979528901238B401342D3 +:100FA0000ED1143001F078FE024648B1D4F89444D2 +:100FB0004FF4807361792068BDE8104000F07CB97F +:100FC00010BD0000406BFFF7DBBF00007047000062 +:100FD0007FB5124B036000234360C0E90233012553 +:100FE00002260F4B057404460290019300F184021F +:100FF000294600964FF48073143001F029FE094B06 +:101000000294CDE9006304F523724FF480732946FE +:1010100004F14C0001F0ECFE04B070BDAC360008E9 +:10102000C50F0008ED0E000808B50A68FFF750FF6D +:101030000B7902EB830318624B790D3342F82300DE +:101040008B7913B102EB830210620223C0F894146F +:101050000374002080F3118808BD000038B5037FB9 +:10106000044613B190F85430ABB9201D012502217C +:10107000FFF734FF04F1140025776FF0010100F051 +:1010800079FC84F8545004F14C006FF00101BDE884 +:10109000384000F06FBC38BD10B501210446043063 +:1010A000FFF71CFF0023237784F8543010BD0000A5 +:1010B00038B504460025143001F0E2FD04F14C007F +:1010C000257701F0ADFE201D84F854500121FFF773 +:1010D00005FF2046BDE83840FFF752BF90F85C306E +:1010E00003F06003202B07D190F85D20212A4FF0F8 +:1010F000000303D81F2A06D800207047222AFBD1FC +:10110000C0E9143303E0034A0265072242658365A0 +:10111000012070472C22012037B5D0F894341A688A +:101120001178042904461AD1017C022917D11979B2 +:10113000128901238B40134211D100F14C0528463E +:1011400001F02CFF58B101A9284601F075FED4F832 +:101150009444019B21790246206800F0BFF803B057 +:1011600030BD0000F0B500EB810385B01E6A044677 +:101170000D46F6B104EB8507301D0821FFF7A8FEE8 +:10118000FFF7ACFEFB685B691B6806F14C001BB106 +:10119000019001F05FFE019803A901F04DFE0246A7 +:1011A00048B1039B2946204600F098F8002383F3BA +:1011B000118805B0F0BDFB685A691268002AF5D0A5 +:1011C0001B8A013B1340F1D104F15C02EAE7000005 +:1011D0000D3138B550F82140D4B1FFF779FED4F87D +:1011E00094241368527903EB8203DB689B695D6882 +:1011F00045B104216018FFF771FE294604F114007F +:1012000001F054FD2046FFF7BBFE002383F3118855 +:1012100038BD00007047000072B6302383F3118898 +:1012200062B6704701F08EB810B50123044628223B +:1012300000F8243B0021FFF7B5FD0023C4E901338A +:1012400010BD000038B50025FFF7E6FF0446C0E9F1 +:101250000355C0E90555C0E90755416001F082F822 +:101260000223237085F31188284638BD70B500EB42 +:10127000810305465069DA600E46144618B1102203 +:101280000021FFF78FFDA06918B110220021FFF7A0 +:1012900089FD31462846BDE8704001F02DB90000B7 +:1012A000826802F0011282600022C0E90422C0E9D3 +:1012B0000622026201F0ACB9F0B400EB8104478968 +:1012C000E4680125A4698D403D43458123600023E6 +:1012D000A2606360F0BC01F0C7B90000F0B400EB9D +:1012E00081040789E468012564698D403D430581D7 +:1012F00023600023A2606360F0BC01F043BA0000E9 +:1013000070B50223002504460370C0E90255C0E908 +:101310000455C0E906554566056280F84C5001F059 +:1013200087F863681B6823B129462046BDE87040F2 +:10133000184770BD0378052B10B504460AD080F815 +:1013400068300523037043681B680BB1042198477C +:101350000023A36010BD00000178052906D190F894 +:101360006820436802701B6803B11847704700008B +:1013700070B590F84C30044613B1002380F84C301F +:1013800004F15C02204601F065F963689B68B3B91B +:1013900094F85C3013F0600533D00021204601F052 +:1013A0001DFC0021204601F00FFC63681B6813B18F +:1013B000062120469847062384F84C3070BD20460D +:1013C00098470028E4D0B4F86230626D9A4288BF32 +:1013D000636594F95C30656D002B80F20281002D0D +:1013E00000F0F180092384F84C30FFF715FF00214D +:1013F000D4E914232046FFF771FF002383F31188FB +:10140000DCE794F85D2003F07F0343EA022340F217 +:101410000232934200F0C48021D8B3F5807F48D0D7 +:101420000DD8012B3FD0022B00F09280002BB4D1BD +:1014300004F16402226502226265A365C3E7B3F585 +:10144000817F00F09A80B3F5407FA6D194F85E309A +:10145000012BA2D1B4F8643043F0020332E0B3F5BB +:10146000006F4DD017D8B3F5A06F31D0A3F5C0638E +:10147000012B92D8636894F85E205E6894F85F1040 +:10148000B4F860302046B047002886D04368236512 +:10149000036863651AE0B3F5106F36D040F6024278 +:1014A00093427FF47AAF5B4B23650223636500238D +:1014B000C3E794F85E30012B7FF46FAFB4F864306B +:1014C00023F00203C4E91455A4F86430A5657AE753 +:1014D000B4F85C30B3F5A06F0ED194F85E3084F8A8 +:1014E0006630204600F0FCFF63681B6813B10121E1 +:1014F00020469847032323700023C4E914339CE754 +:1015000004F1670323650123C3E72378042B0FD17C +:101510002046FFF781FEFFF7C3FE85F31188032104 +:10152000636884F8675021701B680BB120469847A8 +:1015300094F85E30002BDFD084F8673004232370EA +:1015400063681B68002BD7D0022120469847D3E759 +:1015500094F860301D0603F00F0120460AD501F013 +:101560006BF8012804D002287FF417AF2A4B9BE7C1 +:101570002A4B99E701F052F8F3E794F85E30002B1C +:101580007FF40BAF94F8603013F00F01B4D01A065B +:10159000204602D501F036FBAEE701F029FBABE7B0 +:1015A00094F85E30002B7FF4F8AE94F8603013F0BE +:1015B0000F01A1D01B06204602D501F00FFB9BE7CF +:1015C00001F002FB98E7142384F84C30FFF724FE67 +:1015D0002A462B4629462046FFF76EFE85F31188E2 +:1015E000ECE65DB1152384F84C30FFF715FE0021C1 +:1015F000D4E914232046FFF75FFEFEE60B2384F8B0 +:101600004C30FFF709FE2A462B4629462046FFF7B5 +:1016100065FEE3E7DC360008D4360008D83600085B +:1016200038B590F84C300446002B3CD0063BDAB27B +:101630000F2A32D80F2B30D8DFE803F0352F2F08D0 +:1016400021302F2F2F2F2F2F2F2F3535456DB0F80D +:1016500062309D4213D2C3681B8AB5FBF3F203FBD1 +:10166000125565B9FFF7D8FD2A462B462946FFF7E4 +:1016700035FE85F311880A2384F84C300DE01423DD +:1016800084F84C30FFF7C8FD00231A46194620465F +:10169000FFF712FE002383F3118838BD836D03B179 +:1016A00098470023E8E70021204601F097FA00213F +:1016B000204601F089FA63681B6813B106212046B1 +:1016C00098470623D8E7000010B590F84C30142B4B +:1016D000044628D017D8062B05D001D81BB110BD61 +:1016E000093B022BFBD80021204601F077FA0021AC +:1016F000204601F069FA63681B6813B10621204691 +:101700009847062318E0152BE9D10B2380F84C30BD +:10171000FFF782FD00231A461946FFF7DFFD00237D +:1017200083F31188DBE7C3689B695B68002BD6D124 +:10173000836D03B19847002384F84C30CFE7000055 +:1017400000230375826803691B6899689142FBD284 +:101750005A68036042601060586070470023037548 +:10176000826803691B6899689142FBD85A680360D4 +:10177000426010605860704708B5084672B6302362 +:1017800083F3118862B60B7D032B05D0042B0DD09B +:101790002BB983F3118808BD8B6900221A604FF0C2 +:1017A000FF338361FFF7CCFF0023F2E7D1E900327A +:1017B00013605A60F3E70000FFF7C2BF054BD9681A +:1017C0000875186802681A60536001220275D860B3 +:1017D000FEF7A8BDB823012030B50C4BDD684B1CCB +:1017E00087B004460FD02B46094A684600F056F9E8 +:1017F0002046FFF7E3FF009B13B1684600F058F95D +:10180000A86907B030BDFFF7D9FFF9E7B823012079 +:1018100079170008044B1A68DB6890689B68984247 +:1018200094BF002001207047B8230120084B10B559 +:101830001C68D86822681A60536001222275DC6037 +:10184000FFF78CFF01462046BDE81040FEF76ABD59 +:10185000B823012038B5074C074908480123002563 +:101860002370656001F0D2FB0223237085F3118899 +:1018700038BD00BF20260120E4360008B82301202F +:1018800000F04CB9034A516853685B1A9842FBD880 +:10189000704700BF001000E072B6302383F3118858 +:1018A00062B670478B60022308618B8208467047DE +:1018B0008368A3F1840243F8142C026943F8442C92 +:1018C000426943F8402C094A43F8242CC26843F883 +:1018D000182C022203F80C2C002203F80B2C044ACB +:1018E00043F8102CA3F12000704700BF3D0300080F +:1018F000B823012008B5FFF7DBFFBDE80840FFF77C +:101900005BBF0000024BDB6898610F20FFF756BFFA +:10191000B823012008B5FFF7BFFFBDE80840FFF777 +:10192000F1BF000008B501460820FFF7B5FFFFF73B +:1019300053FF002383F3118808BD0000064BDB68CA +:1019400039B1426818605A60136043600420FFF7A1 +:1019500043BF4FF0FF307047B8230120036898421F +:1019600006D01A680260506099611846FFF724BFDC +:101970007047000038B504460D462068844200D107 +:1019800038BD036823605C608561FFF715FFF4E7ED +:1019900010B503689C68A2420CD85C688A600B6032 +:1019A0004C602160596099688A1A9A604FF0FF3341 +:1019B000836010BD1B68121BECE700000A2938BFCA +:1019C0000A2170B504460D460A26601901F018FB7D +:1019D00001F004FB041BA54203D8751C2E460446E7 +:1019E000F3E70A2E04D9BDE87040012001F04EBB98 +:1019F00070BD0000F8B5144B0D46D96103F110011C +:101A000041600A2A1969826038BF0A220160486071 +:101A10001861A818144601F0E5FA0A2701F0DEFA69 +:101A2000431BA342064606D37C1C281901F0E8FAA2 +:101A300027463546F2E70A2F04D9BDE8F8400120D1 +:101A400001F024BBF8BD00BFB8230120F8B506465D +:101A50000D4601F0C3FA0F4A134653F8107F9F4218 +:101A600006D12A4601463046BDE8F840FFF7C2BF1E +:101A7000D169BB68441A2C1928BF2C46A34202D94D +:101A80002946FFF79BFF224631460348BDE8F84050 +:101A9000FFF77EBFB8230120C823012010B4C0E99E +:101AA000032300235DF8044B4361FFF7CFBF000021 +:101AB00010B5194C236998420DD0D0E900328168E5 +:101AC00013605A609A680A449A60002303604FF0DA +:101AD000FF33A36110BD2346026843F8102F536003 +:101AE0000022026022699A4203D1BDE8104001F051 +:101AF00081BA936881680B44936001F06FFA2269A0 +:101B0000E1699268441AA242E4D91144BDE8104048 +:101B1000091AFFF753BF00BFB82301202DE9F04792 +:101B2000DFF8C08008F110072D4ED8F8105001F0F2 +:101B300055FAD8F81C40AA68031B9A4240D81444AE +:101B4000D5E900324FF00009C8F81C4013605A6014 +:101B5000C5F80090D8F81030B34201D101F04AFA2C +:101B600089F31188D5E903312846984772B63023A6 +:101B700083F3118862B66B69002BD6D001F02EFA80 +:101B80006A69A0EB04094A4582460DD2022001F0A1 +:101B90007DFA0022D8F81030B34208D151462846C9 +:101BA000BDE8F047FFF726BF121A2244F2E712EB16 +:101BB000090938BF4A4629463846FFF7E9FEB3E728 +:101BC000D8F81030B34208D01444211AC8F81C00C9 +:101BD000A960BDE8F047FFF7F1BEBDE8F08700BFA0 +:101BE000C8230120B823012000207047FEE7000031 +:101BF000704700004FF0FF307047000072B630238E +:101C000083F3118862B6704702290CD0032904D0EF +:101C10000129074818BF00207047032A05D8054846 +:101C200000EBC2007047044870470020704700BFB7 +:101C3000BC3700083C2201207037000870B59AB00C +:101C40000546084601A9144600F0BEF801A8FFF7B2 +:101C5000A1F8431C5B00C5E9003400222370032374 +:101C60006370C6B201AB02341046D1B28E4204F1A9 +:101C7000020401D81AB070BD13F8011B04F8021C4D +:101C800004F8010C0132F0E708B50448FFF7B6FF8D +:101C9000FFF742FA002383F3118808BD28260120AC +:101CA00090F85C3003F01F02012A07D190F85D2004 +:101CB0000B2A03D10023C0E9143315E003F06003BD +:101CC000202B08D1B0F860302BB990F85D20212A84 +:101CD00003D81F2A04D8FFF701BA222AEBD0FAE76B +:101CE000034A02650722426583650120704700BFF1 +:101CF0003322012007B5052916D8DFE801F01815B1 +:101D00000318181E104A0121FFF778FF0190FFF712 +:101D1000ADFA01980D4A0221FFF7A8FA0C48FFF727 +:101D2000C7F9002383F3118803B05DF804FB08486A +:101D3000FFF764FFFFF792F9F3E70548FFF75EFF4F +:101D4000FFF7AAF9EDE700BF1037000834370008A5 +:101D50002826012038B50C4D0C4C0D492A4604F1BB +:101D60000800FFF76BFF05F1CA0204F110000949F2 +:101D7000FFF764FF05F5CA7204F118000649BDE8D3 +:101D80003840FFF75BBF00BFF02A01203C22012052 +:101D9000F0360008FA3600080537000870B504462A +:101DA00008460D46FEF7F6FFC6B22046013403781A +:101DB0000BB9184670BD32462946FEF7D7FF0028FA +:101DC000F3D10120F6E700002DE9F84F05460C4657 +:101DD000FEF7E0FF2B49C6B22846FFF7DFFF08B148 +:101DE0000236F6B228492846FFF7D8FF08B1103668 +:101DF000F6B2632E0DD8DFF88C80DFF88C90234F7D +:101E0000DFF890A0DFF890B02E7846B92670BDE8D4 +:101E1000F88F29462046BDE8F84F01F029BC252E51 +:101E20002BD1072241462846FEF7A0FF58B9DBF820 +:101E300000302360DBF8043063609BF808302372C5 +:101E400007350934E0E7082249462846FEF78EFFA9 +:101E500098B90F4BA21C197809090232C95D02F822 +:101E6000041C13F8011B01F00F015345C95D02F872 +:101E7000031CF0D118340835C6E704F8016B0135AE +:101E8000C2E700BFDC37000805370008EE3700085E +:101E900020F4F01F2CF4F01FE4370008BFF34F8F3D +:101EA000024AD368DB03FCD4704700BF003C024009 +:101EB00008B5074B1B7853B9FFF7F0FF054B1A69BC +:101EC000002ABFBF044A5A6002F188325A6008BD36 +:101ED0004E2D0120003C02402301674508B5054B0B +:101EE0001B7833B9FFF7DAFF034A136943F0004365 +:101EF000136108BD4E2D0120003C02400728F0B5BB +:101F000016D80C4C0C4923787BB90C4D0E4608238F +:101F10004FF0006255F8047B46F8042B013B13F0A8 +:101F2000FF033A44F6D10123237051F82000F0BD9D +:101F30000020FCE7702D0120502D01200038000802 +:101F4000014B53F820007047003800080820704704 +:101F5000072810B5044601D9002010BDFFF7CEFFB9 +:101F6000064B53F824301844C21A0BB90120F4E789 +:101F700012680132F0D1043BF6E700BF00380008D8 +:101F8000072810B5044621D8FFF788FFFFF790FF18 +:101F90000F4AF323D360C300DBB243F4007343F072 +:101FA00002031361136943F480331361FFF776FF73 +:101FB000FFF7A4FF074B53F8241000F0D9F8FFF700 +:101FC0008DFF2046BDE81040FFF7C2BF002010BDC6 +:101FD000003C024000380008F8B512F00103144636 +:101FE00042D18218B2F1016F57D82D4B1B6813F004 +:101FF000010352D02B4DFFF75BFFF323EB60FFF79C +:102000004DFF40F20127032C15D824F00104661877 +:10201000244C401A40F20117B142236900EB01053C +:1020200024D123F001032361FFF758FF0120F8BDFD +:10203000043C0430E7E78307E7D12B6923F44073BE +:102040002B612B693B432B6151F8046B0660BFF396 +:102050004F8FFFF723FF03689E42E9D02B6923F0DF +:1020600001032B61FFF73AFF0020E0E723F4407300 +:10207000236123693B4323610B882B80BFF34F8F80 +:10208000FFF70CFF2D8831F8023BADB2AB42C3D055 +:10209000236923F001032361E4E71846C7E700BF83 +:1020A00000380240003C0240084908B50B7828B1CE +:1020B0001BB9FFF7FDFE01230B7008BD002BFCD000 +:1020C000BDE808400870FFF709BF00BF4E2D012092 +:1020D00010B50244064BD2B2904200D110BD441C50 +:1020E00000B253F8200041F8040BE0B2F4E700BF5F +:1020F000502800400F4B30B51C6F240407D41C6FD0 +:1021000044F400741C671C6F44F400441C670A4CC0 +:10211000236843F4807323600244084BD2B2904298 +:1021200000D130BD441C00B251F8045B43F820508C +:10213000E0B2F4E700380240007000405028004050 +:1021400007B5012201A90020FFF7C2FF019803B0E3 +:102150005DF804FB13B50446FFF7F2FFA04205D07B +:10216000012201A900200194FFF7C4FF02B010BDB5 +:102170000144BFF34F8F064B884204D3BFF34F8F08 +:10218000BFF36F8F7047C3F85C022030F4E700BFE5 +:1021900000ED00E0034B1A681AB9034AD2F874281C +:1021A0001A607047742D01200030024008B5FFF717 +:1021B000F1FF024B1868C0F3407008BD742D012078 +:1021C00070B5BFF34F8FBFF36F8F1A4A0021C2F86B +:1021D0005012BFF34F8FBFF36F8F536943F4003337 +:1021E0005361BFF34F8FBFF36F8FC2F88410BFF3FB +:1021F0004F8FD2F88030C3F3C900C3F34E335B0175 +:1022000043F6E07403EA0406014646EA81750139A3 +:10221000C2F86052F9D2203B13F1200FF2D1BFF384 +:102220004F8F536943F480335361BFF34F8FBFF334 +:102230006F8F70BD00ED00E0FEE7000070B5214B30 +:102240002148224A904237D3214BDA1C121AC11E70 +:1022500022F003028B4238BF00220021FEF7A2FDCC +:102260001C4A0023C2F88430BFF34F8FD2F880306D +:10227000C3F3C900C3F34E335B0143F6E07403EAD2 +:102280000406014646EA81750139C2F86C52F9D25A +:10229000203B13F1200FF2D1BFF34F8FBFF36F8FAD +:1022A000BFF34F8FBFF36F8F0023C2F85032BFF3DD +:1022B0004F8FBFF36F8F70BD53F8041B40F8041BA2 +:1022C000C0E700BFEC390008882E0120882E0120CD +:1022D000882E012000ED00E070B5D0E91B439E6818 +:1022E00000224FF0FF3504EB42135101D3F80009EF +:1022F0000028BEBFD3F8000940F08040C3F80009B1 +:10230000D3F8000B0028BEBFD3F8000B40F080408C +:10231000C3F8000B013263189642C3F80859C3F89A +:10232000085BE0D24FF00113C4F81C3870BD000008 +:10233000890141F02001016103699B06FCD4122050 +:10234000FFF7A0BA10B5054C2046FEF76DFF4FF021 +:10235000A043E366024B236710BD00BF782D012028 +:102360004438000870B50378012B054650D12A4B3C +:10237000C46E98421BD1294B5A6B42F080025A63BB +:102380005A6D42F080025A655A6D5A6942F08002D5 +:102390005A615A6922F080025A610E2143205B691A +:1023A00000F03AFC1E4BE3601E4BC4F800380023DB +:1023B000C4F8003EC0232360EE6E4FF40413A36301 +:1023C0003369002BFCDA012333610C20FFF75AFA42 +:1023D0003369DB07FCD41220FFF754FA3369002B72 +:1023E000FCDA0026A6602846FFF776FF6B68C4F883 +:1023F0001068DB68C4F81468C4F81C684BB90A4B51 +:10240000A3614FF0FF336361A36843F00103A3604E +:1024100070BD064BF4E700BF782D01200038024064 +:102420004014004003002002003C30C0083C30C093 +:10243000F8B5C46E054600212046FFF779FF296FE5 +:1024400000234FF001128F68C4F834384FF0006653 +:10245000C4F81C284FF0FF3004EB431201339F42B5 +:10246000C2F80069C2F8006BC2F80809C2F8080B8C +:10247000F2D20B68EA6E6B67636210231361166910 +:1024800016F01006FBD11220FFF7FCF9D4F8003843 +:1024900023F4FE63C4F80038A36943F4402343F0F7 +:1024A0001003A3610923C4F81038C4F814380A4B88 +:1024B000EB604FF0C043C4F8103B084BC4F8003B3E +:1024C000C4F81069C4F800396B6F03F1100243F4CB +:1024D00080136A67A362F8BD2038000840800010AE +:1024E000C26E90F86610D2F8003823F4FE6343EA17 +:1024F0000113C2F8003870472DE9F84300EB81035F +:10250000C56EDA68166806F00306731E022B05EB2B +:1025100041130C4680460FFA81F94FEA41104FF003 +:102520000001C3F8101B4FF0010104F1100398BF24 +:10253000B60401FA03F391698EBF334E06F180565B +:1025400006F5004600293AD0578A04F1580149019E +:1025500037436F50D5F81C180B43C5F81C382B189F +:102560000021C3F8101953690127611EA7409BB3CE +:10257000138A928B9B08012A88BF5343D8F8742092 +:10258000981842EA034301F1400205EB8202C8F8C1 +:102590007400214653602846FFF7CAFE08EB890005 +:1025A000C3681B8A43EA8453483464011E432E5196 +:1025B000D5F81C381F43C5F81C78BDE8F88305EB37 +:1025C0004917D7F8001B21F40041C7F8001BD5F8C4 +:1025D0001C1821EA0303C0E704F13F0305EB830362 +:1025E0000A4A5A6028462146FFF7A2FE05EB491029 +:1025F000D0F8003923F40043C0F80039D5F81C386E +:1026000023EA0707D7E700BF00800010000400029C +:10261000026F12684267FFF75FBE00005831C36E59 +:1026200049015B5813F4004004D013F4001F0CBFA1 +:1026300002200120704700004831C36E49015B58F9 +:1026400013F4004004D013F4001F0CBF022001203B +:102650007047000000EB8101CB68196A0B681360BA +:102660004B6853607047000000EB810330B5DD68B4 +:10267000AA691368D36019B9402B84BF4023136043 +:102680006B8A1468C26E1C44013CB4FBF3F46343D0 +:10269000033323F0030302EB411043EAC44343F046 +:1026A000C043C0F8103B2B6803F00303012B09B2B1 +:1026B0000ED1D2F8083802EB411013F4807FD0F825 +:1026C000003B14BF43F0805343F00053C0F8003B7D +:1026D00002EB4112D2F8003B43F00443C2F8003B46 +:1026E00030BD00002DE9F041254DEE6E06EB4013A4 +:1026F0000446D3F8087BC3F8087B38070AD5D6F818 +:102700001438190706D505EB84032146DB682846F3 +:102710005B689847FA0721D5D6F81438DB071DD532 +:1027200005EB8403D968DCB98B69488A5A68B2FB27 +:10273000F0F600FB16229AB91868DA6890420FD2B8 +:10274000121AC3E9002472B6302383F3118862B6EB +:102750000B482146FFF788FF84F31188BDE8F0811C +:10276000012303FA04F26B8923EA02036B81CB682D +:10277000002BF3D021460248BDE8F041184700BFC6 +:10278000782D012000EB810370B5DD68C36E6C69A4 +:102790002668E6604A0156BB1A444FF40020C2F88E +:1027A00010092A6802F00302012A0AB20ED1D3F8F6 +:1027B000080803EB421410F4807FD4F8000914BF1A +:1027C00040F0805040F00050C4F8000903EB421282 +:1027D000D2F8000940F00440C2F80009D3F83408E8 +:1027E000012202FA01F10143C3F8341870BD19B98E +:1027F000402E84BF4020206020682E8A8419013C2E +:10280000B4FBF6F440EAC44040F000501A44C6E776 +:102810002DE9F8433C4DEE6E06EB40130446D3F829 +:102820000889C3F8088918F0010F4FEA40171CD037 +:10283000D6F81038DB0718D505EB8003D9684B694B +:102840001868DA68904232D2121A4FF000091A6002 +:10285000C3F8049072B6302383F3118862B6214620 +:102860002846FFF78FFF89F3118818F0800F1CD0DE +:10287000D6F834380126A640334216D005EB84033F +:10288000ED6ED3F80CC0DCF814200134E4B2D2F8B9 +:1028900000E005EB04342F445168714515D3D5F899 +:1028A000343823EA0606C5F83468BDE8F883012306 +:1028B00003FA04F22B8923EA02032B818B68002B95 +:1028C000D3D0214628469847CFE7BCF81000AEEB9E +:1028D0000103834228BF0346D7F8180980B2B3EB3F +:1028E000800FE2D89068A0F1040959F8048FC4F869 +:1028F0000080A0EB09089844B8F1040FF5D81844FB +:102900000B4490605360C7E7782D01202DE9F74F05 +:10291000AC4CE56E6E69AB691E4016F480586E6172 +:1029200007D02046FEF7ECFC03B0BDE8F04F00F006 +:102930006BBC002E12DAD5F8003EA2489B071EBFE2 +:10294000D5F8003E23F00303C5F8003ED5F804385F +:1029500023F00103C5F80438FEF7FEFC370505D562 +:102960009848FFF7B9FC9748FEF7E4FCB0040CD593 +:10297000D5F8083813F0060FEB6823F470530CBF3A +:1029800043F4105343F4A053EB6031071BD5636845 +:10299000DB681BB9AB6923F00803AB612378052B17 +:1029A0000CD1D5F8003E87489A071EBFD5F8003EE7 +:1029B00023F00303C5F8003EFEF7CEFC6368DB6836 +:1029C0000BB180489847F30200F18980B70227D500 +:1029D000D4F86C90DFF8ECB100274FF0010A09EB56 +:1029E0004712D2F8003B03F44023B3F5802F11D1F6 +:1029F000D2F8003B002B0DDA62890AFA07F322EACB +:102A00000303638104EB8703DB68DB6813B139469A +:102A100058469847236F01379B68FFB29F42DED923 +:102A2000F00617D5E76E3A6AC2F30A1002F00F03F8 +:102A300002F4F012B2F5802F00F09980B2F5402F29 +:102A400008D104EB83030022DB681B6A07F580577B +:102A500090427ED13303D5F818481DD5E70302D53F +:102A60000020FFF73FFEA50302D50120FFF73AFE45 +:102A7000600302D50220FFF735FE210302D50320B3 +:102A8000FFF730FEE20202D50420FFF72BFEA3027F +:102A900002D50520FFF726FE77037FF545AFE60751 +:102AA00002D50020FFF7B4FEA50702D50120FFF7ED +:102AB000AFFE600702D50220FFF7AAFE210702D56C +:102AC0000320FFF7A5FEE20602D50420FFF7A0FED3 +:102AD000A3067FF529AF0520FFF79AFE24E7E36EF2 +:102AE000DFF8E0A0019300274FF00109236F9B68F6 +:102AF0005FFA87FB9B453FF669AF019B03EB4B13E6 +:102B0000D3F8001901F44021B1F5802F1FD1D3F87B +:102B1000001900291BDAD3F8001941F09041C3F8DD +:102B20000019D3F800190029FBDB5946E06EFFF7C6 +:102B3000FFFB218909FA0BF321EA0303238104EB4C +:102B40008B03DB689B6813B15946504698470137A1 +:102B5000CCE7910708BFD7F80080072A98BF03F891 +:102B6000018B02F1010298BF4FEA182870E7023387 +:102B700004EB830207F580575268D2F818C0DCF8DE +:102B80000820DCE9001CA1EB0C0C002188420AD1D2 +:102B900004EB830463689B699A6802449A605A68EC +:102BA00002445A6056E711F0030F08BFD7F80080BF +:102BB0008C4588BF02F8018B01F1010188BF4FEA03 +:102BC0001828E3E7782D0120C36E03EB4111D1F8FB +:102BD000003B43F40013C1F8003B7047C36E03EBA6 +:102BE0004111D1F8003943F40013C1F8003970479E +:102BF000C36E03EB4111D1F8003B23F40013C1F87D +:102C0000003B7047C36E03EB4111D1F8003923F448 +:102C10000013C1F80039704700F1604303F56143C8 +:102C20000901C9B283F80013012200F01F039A4082 +:102C300043099B0003F1604303F56143C3F880211E +:102C40001A60704772B6302383F3118862B67047FA +:102C500030B5039C0172043304FB0325C0E906531D +:102C6000049B03630021059BC160C0E90000C0E92B +:102C70000422C0E90842C0E90A11436330BD0000E4 +:102C8000416A0022C0E90411C0E90A22C2606FF063 +:102C90000101FEF76FBE0000D0E90432934201D17A +:102CA000C2680AB9181D704700207047036919608F +:102CB000C2680132C260C2691344826903619342EF +:102CC00024BF436A03610021FEF748BE38B50446BD +:102CD0000D46E3683BB16269131D1268A362134499 +:102CE000E362002007E0237A33B929462046FEF745 +:102CF00025FE0028EDDA38BD6FF00100FBE700008B +:102D0000C368C269013BC36043691344826943617C +:102D1000934224BF436A436100238362036B03B180 +:102D20001847704770B5FFF78DFF866A04463EB9B5 +:102D3000FFF7CCFF054618B186F31188284670BD11 +:102D4000A36AE26A13F8015BA362934202D32046AE +:102D5000FFF7D6FF002383F31188EFE72DE9F04753 +:102D60009846FFF76FFF002504460E461746A94612 +:102D7000D4F828A0BAF1000F09D141462046FFF748 +:102D8000A5FF20B18AF311882846BDE8F087D4E971 +:102D90000A12A7EB050A521A924528BF9246BAF1C9 +:102DA000400F1BD9334601F1400251F8040B43F8A0 +:102DB000040B9142F9D1A36A40334036A3624035F7 +:102DC000D4E90A239A4202D32046FFF799FF89F3F8 +:102DD0001188BD42D8D2FFF735FFC9E730465246C9 +:102DE000FDF7BAFFA36A53445644A3625544E7E78C +:102DF00010B5029C0172043303FB0421C0E90613E1 +:102E00000023C0E90A33039B0363049BC460C0E949 +:102E10000000C0E90422C0E90842436310BD00007D +:102E2000026AC260426AC0E904220022C0E90A22A2 +:102E30006FF00101FEF79EBDD0E904239A4201D153 +:102E4000C26822B9184650F8043B0B607047002353 +:102E50001846FAE7C368C2690133C3604369134483 +:102E600082694361934224BF436A43610021FEF7B4 +:102E700075BD000038B504460D46E3683BB12369D3 +:102E80001A1DA262E2691344E362002007E0237A7C +:102E900033B929462046FEF751FD0028EDDA38BD4A +:102EA0006FF00100FBE7000003691960C268013A96 +:102EB000C260C269134482690361934224BF436ABA +:102EC000036100238362036B03B11847704700005E +:102ED00070B5FFF7B7FE866A0D46044611462EB957 +:102EE000FFF7C8FF10B186F3118870BDA36A1D708B +:102EF000A36AE26A01339342A36204D3E1692046E4 +:102F00000439FFF7D1FF002080F31188EDE70000BE +:102F10002DE9F0479946FFF795FE002604460D4639 +:102F20009046B246A76A4FB949462046FFF7A2FF2E +:102F300020B187F311883046BDE8F087D4E90A074D +:102F40003A1AA8EB0607974228BF1746402F1BD90D +:102F500005F1400355F8042B40F8042B9D42F9D1AC +:102F6000A36A4033A3624036D4E90A239A4204D3C9 +:102F7000E16920460439FFF797FF8AF31188464537 +:102F8000D9D2FFF75FFECDE729463A46FDF7E4FECA +:102F9000A36A3B443D44A3623E44E5E7D0E90423F1 +:102FA0009A4217D1C3689BB1836A8BB1043B9B1AC9 +:102FB0000ED01360C368013BC360C3691A448369C0 +:102FC00002619A4224BF436A0361002383620123A2 +:102FD000184670470023FBE700F042B94FF08043EA +:102FE000586A70474FF08043002258631A610222EA +:102FF000DA6070474FF080430022DA6070470000CB +:103000004FF0804358637047FEE7000070B51B4BDC +:1030100001630025044686B0586085620E4600F0C4 +:10302000CBF804F11003C4E904334FF0FF33C4E9D3 +:103030000635C4E90044A560E562FFF7CFFF2B46E3 +:103040000246C4E9082304F134010D4A25658023B2 +:103050002046FEF727FC0123E0600A4A0375009230 +:1030600072680192B268CDE90223074B6846CDE948 +:103070000435FEF73FFC06B070BD00BF20260120DE +:10308000503800085538000809300008024AD36A51 +:103090001843D062704700BFB82301204B684360DB +:1030A0008B688360CB68C3600B6943614B690362C3 +:1030B0008B6943620B6803607047000008B52C4BB6 +:1030C0002C481A6940F2FF710A431A611A6922F406 +:1030D000FF6222F007021A611A691A6B0A431A6327 +:1030E0001A6D0A431A65244A1B6D1146FFF7D6FF75 +:1030F00002F11C0100F58060FFF7D0FF02F13801FA +:1031000000F58060FFF7CAFF02F1540100F580600E +:10311000FFF7C4FF02F1700100F58060FFF7BEFF0A +:1031200002F18C0100F58060FFF7B8FF02F1A80101 +:1031300000F58060FFF7B2FF02F1C40100F5806086 +:10314000FFF7ACFF02F1E00100F58060FFF7A6FF9A +:1031500002F1FC0100F58060FFF7A0FF02F58C7121 +:1031600000F58060FFF79AFFBDE8084000F0EEB878 +:1031700000380240000002405C38000808B500F04A +:1031800059FAFEF767FBFFF705F8BDE80840FEF7C0 +:10319000E1BD000070470000EFF3098305494A6B69 +:1031A00022F001024A63683383F30988002383F322 +:1031B0001188704700EF00E0302080F3118862B67C +:1031C0000D4B0E4AD96821F4E0610904090C0A4349 +:1031D000DA60D3F8FC200A4942F08072C3F8FC2080 +:1031E000084AC2F8B01F116841F0010111602022A5 +:1031F000DA7783F82200704700ED00E00003FA055B +:1032000055CEACC5001000E010B572B6302383F384 +:10321000118862B60E4B5B6813F4006314D0F1EEB4 +:10322000103AEFF30984683C4FF08073E361094B77 +:10323000DB6B236684F30988FEF7ECFA10B1064BCA +:10324000A36110BD054BFBE783F31188F9E700BFCD +:1032500000ED00E000EF00E04F030008520300081B +:103260000F4B1A6C42F001021A641A6E42F001020E +:103270001A660C4A1B6E936843F0010393604FF08B +:1032800080436B229A624FF0FF32DA6200229A6129 +:103290005A63DA605A6001225A611A60704700BFAF +:1032A00000380240002004E04FF0804208B5116968 +:1032B000D3680B40D9B2C9439B07116109D572B6D7 +:1032C000302383F3118862B6FEF7DAFA002383F322 +:1032D000118808BD1B4B1A696FEA42526FEA5252BD +:1032E0001A611A69C2F30A021A614FF0FF301A69B3 +:1032F0005A69586100215A6959615A691A6A62F01B +:1033000080521A621A6A02F080521A621A6A5A6A63 +:1033100058625A6A59625A6A0B4A106840F48070BF +:103320001060186F00F44070B0F5007F1EBF4FF4BE +:10333000803018671967536823F40073536000F0F6 +:1033400055B900BF0038024000700040374B4FF0C5 +:1033500080521A64364A4FF4404111601A6842F0B4 +:1033600001021A601A689207FCD59A6822F00302DB +:103370009A602E4B9A6812F00C02FBD1196801F08A +:10338000F90119609A601A6842F480321A601A686A +:103390009003FCD55A6F42F001025A67234B5A6FD3 +:1033A0009107FCD5234A5A601A6842F080721A606D +:1033B0001F4B5A685204FCD51A6842F480321A60D6 +:1033C0005A68D003FCD51A6842F400321A60184AD1 +:1033D00053689903FCD5154B1A689201FCD5164A1F +:1033E0009A6040F20112C3F88C200022C3F89020AA +:1033F000124A40F207331360136803F00F03072BE0 +:10340000FAD10A4B9A6842F002029A609A6802F076 +:103410000C02082AFAD15A6C42F480425A645A6E5D +:1034200042F480425A665B6E704700BF003802402B +:1034300000700040086C400900948838003C02404D +:10344000074A08B5536903F00103536123B1054AE4 +:1034500013680BB150689847BDE80840FFF7D4BE29 +:10346000003C0140082E0120074A08B5536903F0CB +:103470000203536123B1054A93680BB1D0689847A2 +:10348000BDE80840FFF7C0BE003C0140082E012007 +:10349000074A08B5536903F00403536123B1054A91 +:1034A00013690BB150699847BDE80840FFF7ACBEFF +:1034B000003C0140082E0120074A08B5536903F07B +:1034C0000803536123B1054A93690BB1D06998474A +:1034D000BDE80840FFF798BE003C0140082E0120DF +:1034E000074A08B5536903F01003536123B1054A35 +:1034F000136A0BB1506A9847BDE80840FFF784BED5 +:10350000003C0140082E0120164B10B55C6904F404 +:1035100078725A61A30604D5134A936A0BB1D06A34 +:103520009847600604D5104A136B0BB1506B98474F +:10353000210604D50C4A936B0BB1D06B9847E2057A +:1035400004D5094A136C0BB1506C9847A30504D5F8 +:10355000054A936C0BB1D06C9847BDE81040FFF75B +:1035600053BE00BF003C0140082E0120194B10B58E +:103570005C6904F47C425A61620504D5164A136DF5 +:103580000BB1506D9847230504D5134A936D0BB1C9 +:10359000D06D9847E00404D50F4A136E0BB1506EFE +:1035A0009847A10404D50C4A936E0BB1D06E98478E +:1035B000620404D5084A136F0BB1506F9847230477 +:1035C00004D5054A936F0BB1D06F9847BDE8104002 +:1035D000FFF71ABE003C0140082E012008B5FFF796 +:1035E00063FEBDE80840FFF70FBE0000062108B5E6 +:1035F0000846FFF711FB06210720FFF70DFB062108 +:103600000820FFF709FB06210920FFF705FB06212B +:103610000A20FFF701FB06211720FFF7FDFA06211C +:103620002820FFF7F9FABDE8084007211C20FFF722 +:10363000F3BA000008B5FFF74DFE00F00BF8FDF7F8 +:10364000F1FDFDF7C3FCFFF7A5FDBDE80840FFF75E +:10365000C3BC00000023054A19460133102BC2E900 +:10366000001102F10802F8D1704700BF082E0120B6 +:10367000034611F8012B03F8012B002AF9D17047FA +:1036800053544D3332463F3F3F3F3F3F0053544D2D +:10369000333246375B347C355D780053544D3332DA +:1036A00046375B367C375D78000000000000000084 +:1036B000490F0008350F0008710F00085D0F000862 +:1036C000690F0008550F0008410F00082D0F000872 +:1036D0007D0F000800000000010000000000000055 +:1036E00063300000E036000810240120202601206D +:1036F0004172647550696C6F740025424F415244A9 +:10370000252D424C002553455249414C25000000CF +:10371000020000000000000065110008D11100083F +:1037200040004000C02A0120D02A012002000000F1 +:103730000000000003000000000000001512000857 +:103740000000000010000000E02A0120000000003E +:103750000100000000000000782D0120010102009E +:10376000F51C0008091C0008A11C0008891C0008A1 +:10377000430000007837000809024300020100C03E +:1037800032090400000102020100052400100105B5 +:103790002401000104240202052406000107058219 +:1037A000030800FF09040100020A000000070501E8 +:1037B00002400000070581024000000012000000E6 +:1037C000C4370008120110010200004009124157DD +:1037D00000020102030100000403090425424F41D5 +:1037E00052442500426C69747A46373435003031D2 +:1037F0003233343536373839414243444546000088 +:1038000000800000008000000080000000800000B8 +:10381000000002000000040000000400000004009A +:10382000000000007113000821160008C9160008E6 +:1038300040004000F02D0120F02D0120010000008B +:10384000002E012080000000400100000500000063 +:103850006D61696E0069646C650000000001806A3A +:1038600000000000AAAAAAAA00010064FFFF00004D +:103870000000000000A00A0000000000000000009E +:10388000AAAAAAAA00000000FFFF00000000000092 +:10389000000000000000040000000000AAAAAAAA7C +:1038A00000000000FFFD000000000000000000001C +:1038B0000000000000000000AAAAAAAA0000000060 +:1038C000FFFF0000000000000000000000010000F9 +:1038D00000000000AAAAAAAA00010000FFFF000041 +:1038E00000000000000000000000000000000000D8 +:1038F000AAAAAAAA00000000FFFF00000000000022 +:10390000000000000000000000000000AAAAAAAA0F +:1039100000000000FFFF00000000000000000000A9 +:1039200000000000000000000A000000000000008D +:103930000300000000000000000000000000000084 +:103940000000000000000000000000000000000077 +:103950000000000000000000000000000000000067 +:103960000000000000000000000000000000000057 +:103970000000000000000000000000000000000047 +:103980000000000000000000000000000000000037 +:103990008C0400000000000000800E000000000009 +:1039A000FF0000000000000080360008490400000D +:1039B0008D360008510400009B3600080096000078 +:1039C000000008009600000000080000040000004D +:1039D000D8370008000000000000000000000000D0 +:0C39E000000000000000000000000000DB +:00000001FF diff --git a/Tools/bootloaders/BlitzH743Pro_bl.bin b/Tools/bootloaders/BlitzH743Pro_bl.bin new file mode 100644 index 0000000000000..562d9aa76c514 Binary files /dev/null and b/Tools/bootloaders/BlitzH743Pro_bl.bin differ diff --git a/Tools/bootloaders/BlitzH743Pro_bl.hex b/Tools/bootloaders/BlitzH743Pro_bl.hex new file mode 100644 index 0000000000000..5042a5393809b --- /dev/null +++ b/Tools/bootloaders/BlitzH743Pro_bl.hex @@ -0,0 +1,1103 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200086D2800086C +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008D93D0008053E00085D +:10006000313E00085D3E0008893E0008711000081E +:1000700099100008C5100008F11000081D110008B3 +:100080004511000871110008E3020008E3020008AE +:10009000E3020008E3020008E3020008B53E00089E +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000193F0008E3020008E3020008E3020008E9 +:1000F000E3020008E3020008E30200089D11000883 +:10010000E3020008E30200088D3F0008E302000854 +:10011000E3020008E3020008E3020008E30200082B +:10012000C9110008F11100081D1200084912000849 +:1001300075120008E3020008E3020008E302000869 +:10014000E3020008E3020008E3020008E3020008FB +:100150009D120008C9120008F5120008E302000809 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000859340008E3020008E302000823 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000845340008E3020008E3020008D7 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0F0FA84 +:1003500003F0FEFA4FF055301F491B4A91423CBF53 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F008FB03F05CFBFA +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0F0BA00060020002200207A +:1003D0000000000808ED00E00000002000060020FA +:1003E00068440008002200205C22002060220020D7 +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0A4FDFEE701F056 +:1004300033FD00DFFEE7000038B500F02FFC00F0D0 +:10044000ABFD02F0D3F9054602F006FA0446C0B946 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0CAF90CB100F076 +:1004700075F800F065FD284600F01EF900F06EF8F2 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F021FE0023154A4FF4D1 +:1004D0007A71134801F010FE002383F31188124C47 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F088FC322363602B78032B07D16368EB +:100510002BB9022000F07EFC4FF47A73636038BD83 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F05DBC022000F050BC024B0022F3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F5C0239A4280F088800020C5 +:1005900000F09EFB0220FFF7CBFF454B0021D3F874 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000060820000608FFFF050800220020C1 +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0E3FBB14AB8 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F011FD0023AB4A4FF4F0 +:1006F0007A71A94801F000FD002383F31188009B63 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F06BFB24B19C4B1B6860 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F051FB039B213B1F2B10 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F03FFA0421059005A800F00EFA04 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F058FB26B10BF03D +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F00EFA0220FFF73BFE1FFA86F84046D2 +:1008C00000F016FA0446B0B1039940460136A1F192 +:1008D00040025142514100F01BFA0028EDD1BA46C6 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0E4F9013040F07B +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F032FA019AFF217F4800F053FA4FEAF3 +:1009F000A803C8F387027C492846019300F052FA05 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F096F918 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0F7FA8046E7E7384600F03AF945 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F051F90590E6E70023642104A8CA +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F03FF9EAE717 +:100AC0000220FFF7E5FC00283FF48CAE00F04EF961 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F049F907460421049004A800F0FE +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0CEF80421059005A800F0A1 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F0FBF8002844D00A9B01330BD0CB +:100B600008220AA9002000F09DF900283AD020228E +:100B7000FF210AA800F08EF9FFF792FC1C4801F053 +:100B8000FFF913B0BDE8F08F002E3FF42BAE0BF051 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0DDF9059800F0E4F946463C462E +:100BD00000F0ACF9A6E506464EE64FF0000901E646 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0A8F98B +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B50A4E54 +:100CA00000240A4D01F08AFC308028683388834292 +:100CB00008D901F07FFC2B6804440133B4F5C02F40 +:100CC0002B60F2D370BD00BFB62300208823002024 +:100CD00001F042BD00F1006000F5C02000687047DF +:100CE00000F10060920000F5C02001F0C3BC0000DC +:100CF000054B1A68054B1B889B1A834202D9104486 +:100D000001F058BC0020704788230020B623002043 +:100D100038B50446074D29B128682044BDE838405D +:100D200001F060BC2868204401F04AFC0028F3D0A0 +:100D300038BD00BF882300200020704700F1FF501D +:100D400000F58F10D0F8000870470000064991F8B0 +:100D5000243033B100230822086A81F82430FFF7D9 +:100D6000BFBF0120704700BF8C230020014B1868D3 +:100D7000704700BF0010005C194B01380322084483 +:100D800070B51D68174BC5F30B042D0C1E88A642C9 +:100D90000BD15C680A46013C824213460FD214F91B +:100DA000016F4EB102F8016BF6E7013A03F1080357 +:100DB000ECD181420B4602D22C2203F8012B0424F1 +:100DC000094A1688AE4204D1984284BF967803F847 +:100DD000016B013C02F10402F3D1581A70BD00BF4F +:100DE0000010005C1422002084400008022803D177 +:100DF000024B4FF080729A61704700BF00000258AA +:100E0000022803D1024B4FF480729A61704700BFF1 +:100E100000000258022804D1024A536983F4807307 +:100E2000536170470000025870B504464FF47A765B +:100E30004CB1412C254628BF412506FB05F0641B1B +:100E400001F09EF8F4E770BD002310B5934203D083 +:100E5000CC5CC4540133F9E710BD0000013810B573 +:100E600010F9013F3BB191F900409C4203D11AB106 +:100E70000131013AF4E71AB191F90020981A10BD36 +:100E80001046FCE703460246D01A12F9011B00295E +:100E9000FAD1704702440346934202D003F8011B83 +:100EA000FAE770472DE9F8431F4D14460746884678 +:100EB00095F8242052BBDFF870909CB395F824304D +:100EC0002BB92022FF2148462F62FFF7E3FF95F858 +:100ED00024004146C0F1080205EB8000A24228BF71 +:100EE0002246D6B29200FFF7AFFF95F82430A41B3C +:100EF00017441E449044E4B2F6B2082E85F82460EC +:100F0000DBD1FFF723FF0028D7D108E02B6A03EBE2 +:100F100082038342CFD0FFF719FF0028CBD10020F6 +:100F2000BDE8F8830120FBE78C230020024B1A78F0 +:100F3000024B1A70704700BFB4230020102200201B +:100F400010B5114C114800F06FFB21460F4800F01E +:100F500097FB24684FF47A70D4F89020D2F80438C4 +:100F600043F00203C2F80438FFF75EFF0849204649 +:100F700000F094FCD4F89020D2F8043823F0020357 +:100F8000C2F8043810BD00BF40420008B02600205F +:100F90004842000870470000F0B5A1B071B60023C8 +:100FA0000120002480261A46194600F04BFA4FF41F +:100FB000D067214A3D25136923BBD2F810310BBB02 +:100FC000036804F1006199600368C3F80CD00368FA +:100FD0005E6003681F6001680B6843F001030B60EB +:100FE00001680B6823F01E030B6001680B68DB07C8 +:100FF000FCD4037B8034416805FA03F3B4F5001F89 +:101000000B60D8D100F05EFAB4F5001F11D00024B7 +:101010000A4E0B4D012001F09FFB3388A34205D9F6 +:1010200028682044013401F0DDFAF6E7002001F0E1 +:1010300093FB61B621B0F0BD00200052B623002022 +:101040008823002030B50A44084D91420DD011F894 +:10105000013B5840082340F30004013B2C4013F0AF +:10106000FF0384EA5000F6D1EFE730BD2083B8EDEE +:1010700008B5074B074A196801F03D0199605368AC +:101080000BB190689847BDE8084001F027BC00BF4D +:1010900000000240B823002008B5084B19688909F0 +:1010A00001F03D018A019A60054AD3680BB11069CD +:1010B0009847BDE8084001F011BC00BF00000240A5 +:1010C000B823002008B5084B1968090C01F03D0150 +:1010D0000A049A60054A53690BB190699847BDE8C4 +:1010E000084001F0FBBB00BF00000240B823002015 +:1010F00008B5084B1968890D01F03D018A059A6011 +:10110000054AD3690BB1106A9847BDE8084001F061 +:10111000E5BB00BF00000240B823002008B5074B24 +:10112000074A596801F03D01D960536A0BB1906AD2 +:101130009847BDE8084001F0D1BB00BF0000024065 +:10114000B823002008B5084B5968890901F03D0112 +:101150008A01DA60054AD36A0BB1106B9847BDE883 +:10116000084001F0BBBB00BF00000240B8230020D4 +:1011700008B5084B5968090C01F03D010A04DA6012 +:10118000054A536B0BB1906B9847BDE8084001F0DE +:10119000A5BB00BF00000240B823002008B5084BE3 +:1011A0005968890D01F03D018A05DA60054AD36B63 +:1011B0000BB1106C9847BDE8084001F08FBB00BF31 +:1011C00000000240B823002008B5074B074A196801 +:1011D00001F03D019960536C0BB1906C9847BDE8EC +:1011E000084001F07BBB00BF00040240B823002090 +:1011F00008B5084B1968890901F03D018A019A6018 +:10120000054AD36C0BB1106D9847BDE8084001F05A +:1012100065BB00BF00040240B823002008B5084B9E +:101220001968090C01F03D010A049A60054A536DE2 +:101230000BB1906D9847BDE8084001F04FBB00BF6F +:1012400000040240B823002008B5084B1968890D36 +:1012500001F03D018A059A60054AD36D0BB1106E0D +:101260009847BDE8084001F039BB00BF00040240C8 +:10127000B823002008B5074B074A596801F03D0123 +:10128000D960536E0BB1906E9847BDE8084001F0ED +:1012900025BB00BF00040240B823002008B5084B5E +:1012A0005968890901F03D018A01DA60054AD36E67 +:1012B0000BB1106F9847BDE8084001F00FBB00BFAD +:1012C00000040240B823002008B5084B5968090CF7 +:1012D00001F03D010A04DA60054A536F0BB1906FCB +:1012E0009847BDE8084001F0F9BA00BF0004024089 +:1012F000B823002008B5084B5968890D01F03D015D +:101300008A05DA60054AD36F13B1D2F88000984796 +:10131000BDE8084001F0E2BA00040240B823002012 +:1013200000230C4910B51A460B4C0B6054F82300EF +:10133000026001EB430004334260402BF6D1074AC0 +:101340004FF0FF339360D360C2F80834C2F80C3416 +:1013500010BD00BFB82300209440000800000240E8 +:101360000F28F8B510D9102810D0112811D0122844 +:1013700008D10F240720DFF8C8E00126DEF800506E +:10138000A04208D9002653E00446F4E70F240020C9 +:10139000F1E70724FBE706FA00F73D424AD1264C65 +:1013A0004FEA001C3D4304EB00160EEBC000CEF8E4 +:1013B0000050C0E90123FBB273B12048D0F8D83007 +:1013C00043F00103C0F8D830D0F8003143F00103F6 +:1013D000C0F80031D0F8003117F47F4F0ED0174815 +:1013E000D0F8D83043F00203C0F8D830D0F800313C +:1013F00043F00203C0F80031D0F8003154F80C007B +:10140000036823F01F030360056815F00105FBD195 +:1014100004EB0C033D2493F80CC05F6804FA0CF451 +:101420003C6021240560446112B1987B00F054F8BF +:101430003046F8BD0130A3E794400008004402584C +:10144000B823002010B5302484F31188FFF788FFFB +:10145000002383F3118810BD10B50446807B00F093 +:1014600051F801231549627B03FA02F20B6823EA63 +:101470000203DAB20B6072B9114AD2F8D81021F027 +:101480000101C2F8D810D2F8001121F00101C2F810 +:101490000011D2F8002113F47F4F0ED1084BD3F87E +:1014A000D82022F00202C3F8D820D3F8002122F07D +:1014B0000202C3F80021D3F8003110BDB823002088 +:1014C0000044025808B5302383F31188FFF7C4FFA6 +:1014D000002383F3118808BD090100F16043012254 +:1014E00003F56143C9B283F8001300F01F039A406B +:1014F00043099B0003F1604303F56143C3F8802176 +:101500001A60704700F01F0301229A40430900F15E +:1015100060409B0000F5614003F1604303F56143C7 +:10152000C3F88020C3F88021002380F8003370477F +:10153000026843681143016003B118477047000017 +:1015400013B5406B00F58054D4F8A4381A681178AC +:10155000042914D1017C022911D11979012312899E +:101560008B4013420BD101A94C3002F0A7F8D4F8FC +:10157000A4480246019B2179206800F0DFF902B0FF +:1015800010BD0000143002F029B800004FF0FF3306 +:10159000143002F023B800004C3002F0FBB8000019 +:1015A0004FF0FF334C3002F0F5B80000143001F07A +:1015B000F7BF00004FF0FF31143001F0F1BF000021 +:1015C0004C3002F0C7B800004FF0FF324C3002F050 +:1015D000C1B800000020704710B500F58054D4F861 +:1015E000A4381A681178042917D1017C022914D172 +:1015F0005979012352898B4013420ED1143001F0E6 +:1016000089FF024648B1D4F8A4484FF44073617989 +:101610002068BDE8104000F07FB910BD406BFFF7B7 +:10162000DBBF0000704700007FB5124B0125042688 +:10163000044603600023057400F1840243602946D8 +:10164000C0E902330C4B0290143001934FF4407305 +:10165000009601F03BFF094B04F69442294604F141 +:101660004C000294CDE900634FF4407302F002F89D +:1016700004B070BD944100081D1600084115000813 +:101680000A68302383F311880B790B3342F8230067 +:101690004B79133342F823008B7913B10B3342F8A3 +:1016A000230000F58053C3F8A4180223037400201C +:1016B00080F311887047000038B5037F044613B1EA +:1016C00090F85430ABB90125201D0221FFF730FFFF +:1016D00004F114006FF00101257700F079FC04F1AA +:1016E0004C0084F854506FF00101BDE8384000F020 +:1016F0006FBC38BD10B5012104460430FFF718FF58 +:101700000023237784F8543010BD000038B5044618 +:101710000025143001F0F2FE04F14C00257701F0B1 +:10172000C1FF201D84F854500121FFF701FF20461E +:10173000BDE83840FFF750BF90F8803003F06003F9 +:10174000202B06D190F881200023212A03D81F2ABC +:1017500006D800207047222AFBD1C0E91D3303E0E0 +:10176000034A426707228267C3670120704700BFB0 +:101770002C22002037B500F58055D5F8A4381A681A +:10178000117804291AD1017C022917D11979012372 +:1017900012898B40134211D100F14C04204602F013 +:1017A00041F858B101A9204601F088FFD5F8A448B6 +:1017B0000246019B2179206800F0C0F803B030BDDB +:1017C00001F10B03F0B550F8236085B004460D46D7 +:1017D000FEB1302383F3118804EB8507301D082107 +:1017E000FFF7A6FEFB6806F14C005B691B681BB1A6 +:1017F000019001F071FF019803A901F05FFF02461B +:1018000048B1039B2946204600F098F8002383F353 +:10181000118805B0F0BDFB685A691268002AF5D03E +:101820001B8A013B1340F1D104F18002EAE700007A +:10183000133138B550F82140ECB1302383F31188CF +:1018400004F58053D3F8A4281368527903EB82037C +:10185000DB689B695D6845B104216018FFF768FE8D +:10186000294604F1140001F05FFE2046FFF7B4FEA4 +:10187000002383F3118838BD7047000001F02CB9B4 +:1018800001234022002110B5044600F8303BFFF749 +:1018900001FB0023C4E9013310BD000010B5302363 +:1018A000044683F311882422416000210C30FFF7A5 +:1018B000F1FA204601F032F902230020237080F370 +:1018C000118810BD70B500EB8103054650690E46C6 +:1018D0001446DA6018B110220021FFF7DBFAA06984 +:1018E00018B110220021FFF7D5FA31462846BDE88D +:1018F000704001F019BA000083682022002103F033 +:10190000011310B5044683601030FFF7C3FA204678 +:10191000BDE8104001F094BAF0B4012500EB810459 +:1019200047898D40E4683D43A469458123600023D5 +:10193000A2606360F0BC01F0B1BA0000F0B4012510 +:1019400000EB810407898D40E4683D4364690581AB +:1019500023600023A2606360F0BC01F027BB00009D +:1019600070B5022300250446242203702946C0F8DE +:1019700088500C3040F8045CFFF78CFA204684F85D +:10198000705001F065F963681B6823B12946204651 +:10199000BDE87040184770BD0378052B10B50446AC +:1019A0000AD080F88C300523037043681B680BB1A4 +:1019B000042198470023A36010BD00000178052989 +:1019C00006D190F88C20436802701B6803B1184759 +:1019D0007047000070B590F87030044613B10023D2 +:1019E00080F8703004F18002204601F04DFA6368FF +:1019F0009B68B3B994F8803013F0600535D00021AE +:101A0000204601F03FFD0021204601F02FFD6368D4 +:101A10001B6813B1062120469847062384F87030CE +:101A200070BD204698470028E4D0B4F88630A26FF5 +:101A30009A4288BFA36794F98030A56F002B4FF0BE +:101A4000300380F20381002D00F0F280092284F837 +:101A5000702083F3118800212046D4E91D23FFF76D +:101A60006DFF002383F31188DAE794F8812003F0F7 +:101A70007F0343EA022340F20232934200F0C58022 +:101A800021D8B3F5807F48D00DD8012B3FD0022B51 +:101A900000F09380002BB2D104F188026267022229 +:101AA000A267E367C1E7B3F5817F00F09B80B3F5E0 +:101AB000407FA4D194F88230012BA0D1B4F88830B3 +:101AC00043F0020332E0B3F5006F4DD017D8B3F501 +:101AD000A06F31D0A3F5C063012B90D86368204676 +:101AE00094F882205E6894F88310B4F88430B0478C +:101AF000002884D0436863670368A3671AE0B3F5DE +:101B0000106F36D040F6024293427FF478AF5C4BC0 +:101B100063670223A3670023C3E794F88230012B95 +:101B20007FF46DAFB4F8883023F00203A4F8883056 +:101B3000C4E91D55E56778E7B4F88030B3F5A06FC8 +:101B40000ED194F88230204684F88A3001F0DEF815 +:101B500063681B6813B10121204698470323237053 +:101B60000023C4E91D339CE704F18B036367012361 +:101B7000C3E72378042B10D1302383F31188204648 +:101B8000FFF7BAFE85F311880321636884F88B5050 +:101B900021701B680BB12046984794F88230002BC7 +:101BA000DED084F88B300423237063681B68002B1D +:101BB000D6D0022120469847D2E794F884302046B8 +:101BC0001D0603F00F010AD501F050F9012804D0D9 +:101BD00002287FF414AF2B4B9AE72B4B98E701F0C8 +:101BE00037F9F3E794F88230002B7FF408AF94F8CC +:101BF000843013F00F01B3D01A06204602D501F04D +:101C000059FCADE701F04AFCAAE794F88230002BBA +:101C10007FF4F5AE94F8843013F00F01A0D01B06CA +:101C2000204602D501F02EFC9AE701F01FFC97E751 +:101C3000142284F8702083F311882B462A46294603 +:101C40002046FFF769FE85F31188E9E65DB11522AC +:101C500084F8702083F3118800212046D4E91D23E5 +:101C6000FFF75AFEFDE60B2284F8702083F31188FB +:101C70002B462A4629462046FFF760FEE3E700BFD1 +:101C8000C4410008BC410008C041000838B590F8C4 +:101C900070300446002B3ED0063BDAB20F2A34D80F +:101CA0000F2B32D8DFE803F03731310822323131DF +:101CB0003131313131313737856FB0F886309D425F +:101CC00014D2C3681B8AB5FBF3F203FB12556DB93E +:101CD000302383F311882B462A462946FFF72EFE30 +:101CE00085F311880A2384F870300EE0142384F8F9 +:101CF0007030302383F31188002320461A4619469A +:101D0000FFF70AFE002383F3118838BDC36F03B1C8 +:101D100098470023E7E70021204601F0B3FB0021AC +:101D2000204601F0A3FB63681B6813B1062120461F +:101D300098470623D7E7000010B590F870300446A6 +:101D4000142B29D017D8062B05D001D81BB110BDF4 +:101D5000093B022BFBD80021204601F093FB002118 +:101D6000204601F083FB63681B6813B106212046FF +:101D70009847062319E0152BE9D10B2380F8703022 +:101D8000302383F3118800231A461946FFF7D6FD46 +:101D9000002383F31188DAE7C3689B695B68002B33 +:101DA000D5D1C36F03B19847002384F87030CEE7D4 +:101DB00000238268037503691B6899689142FBD20E +:101DC0005A68036042601060586070470023826860 +:101DD000037503691B6899689142FBD85A680360D0 +:101DE000426010605860704708B50846302383F39E +:101DF00011880B7D032B05D0042B0DD02BB983F359 +:101E0000118808BD8B6900221A604FF0FF3383618F +:101E1000FFF7CEFF0023F2E7D1E9003213605A60EA +:101E2000F3E70000FFF7C4BF054BD96808751868D1 +:101E3000026853601A600122D8600275FEF7E2BAA8 +:101E4000402400200C4B30B5DD684B1C87B00446A5 +:101E50000FD02B46094A684600F04EF92046FFF79E +:101E6000E3FF009B13B1684600F050F9A86907B082 +:101E700030BDFFF7D9FFF9E740240020E91D000835 +:101E8000044B1A68DB6890689B68984294BF0020F6 +:101E90000120704740240020084B10B51C68D8680A +:101EA000226853601A600122DC602275FFF78EFF02 +:101EB00001462046BDE81040FEF7A4BA40240020A9 +:101EC00038B5074C01230025064907482370656093 +:101ED00001F0E6FC0223237085F3118838BD00BFB2 +:101EE000A8260020CC4100084024002000F044B97E +:101EF000034A516853685B1A9842FBD8704700BF89 +:101F0000001000E08B600223086108468B82704756 +:101F10008368A3F1840243F8142C026943F8442C2B +:101F2000426943F8402C094A43F8242CC268A3F1C3 +:101F3000200043F8182C022203F80C2C002203F88E +:101F40000B2C034A43F8102C704700BF1D040008F7 +:101F50004024002008B5FFF7DBFFBDE80840FFF78D +:101F600061BF0000024BDB6898610F20FFF75CBF88 +:101F700040240020302383F31188FFF7F3BF0000D3 +:101F800008B50146302383F311880820FFF75AFF74 +:101F9000002383F3118808BD064BDB6839B1426822 +:101FA00018605A60136043600420FFF74BBF4FF086 +:101FB000FF307047402400200368984206D01A681A +:101FC0000260506018469961FFF72CBF704700000F +:101FD00038B504460D462068844200D138BD0368F8 +:101FE00023605C608561FFF71DFFF4E7036810B5AF +:101FF0009C68A2420CD85C688A600B604C602160CF +:10200000596099688A1A9A604FF0FF33836010BD57 +:10201000121B1B68ECE700000A2938BF0A2170B5C3 +:1020200004460D460A26601901F032FC01F01AFC44 +:10203000041BA54203D8751C04462E46F3E70A2E5E +:1020400004D90120BDE8704001F06ABC70BD0000F9 +:10205000F8B5144B0D460A2A4FF00A07D96103F16F +:102060001001826038BF0A2241601969144601607C +:1020700048601861A81801F0FBFB01F0F3FB431B5B +:102080000646A34206D37C1C28192746354601F094 +:10209000FFFBF2E70A2F04D90120BDE8F84001F068 +:1020A0003FBCF8BD40240020F8B506460D4601F0BF +:1020B000D9FB0F4A134653F8107F9F4206D12A4698 +:1020C00001463046BDE8F840FFF7C2BFD169BB68A2 +:1020D000441A2C1928BF2C46A34202D92946FFF7DF +:1020E0009BFF224631460348BDE8F840FFF77EBF1C +:1020F0004024002050240020C0E90323002310B412 +:102100005DF8044B4361FFF7CFBF000010B5194CD9 +:10211000236998420DD08168D0E9003213605A607B +:102120009A680A449A60002303604FF0FF33A3616A +:1021300010BD0268234643F8102F5360002202604E +:1021400022699A4203D1BDE8104001F09BBB93681D +:1021500081680B44936001F085FB2269E169926814 +:10216000441AA242E4D91144BDE81040091AFFF70D +:1021700053BF00BF402400202DE9F047DFF8BC80AA +:1021800008F110072C4ED8F8105001F06BFBD8F86E +:102190001C40AA68031B9A423ED814444FF0000921 +:1021A000D5E90032C8F81C4013605A60C5F80090A9 +:1021B000D8F81030B34201D101F064FB89F31188E3 +:1021C000D5E9033128469847302383F311886B699A +:1021D000002BD8D001F046FB6A69A0EB04098246C7 +:1021E0004A450DD2022001F09BFB0022D8F81030A6 +:1021F000B34208D151462846BDE8F047FFF728BF53 +:10220000121A2244F2E712EB09092946384638BF70 +:102210004A46FFF7EBFEB5E7D8F81030B34208D0D6 +:102220001444C8F81C00211AA960BDE8F047FFF764 +:10223000F3BEBDE8F08700BF5024002040240020FA +:1022400000207047FEE70000704700004FF0FF30AD +:102250007047000002290CD0032904D00129074847 +:1022600018BF00207047032A05D8054800EBC200BC +:102270007047044870470020704700BFA442000820 +:102280003C2200205842000870B59AB00546084626 +:10229000144601A900F0C2F801A8FEF7F3FD431CA3 +:1022A0000022C6B25B001046C5E900342370032348 +:1022B000023404F8013C01ABD1B202348E4201D8A1 +:1022C0001AB070BD13F8011B013204F8010C04F8B8 +:1022D000021CF1E708B5302383F311880348FFF7A8 +:1022E00049FA002383F3118808BD00BFB0260020FF +:1022F00090F8803003F01F02012A07D190F8812066 +:102300000B2A03D10023C0E91D3315E003F060035D +:10231000202B08D1B0F884302BB990F88120212AE5 +:1023200003D81F2A04D8FFF707BA222AEBD0FAE70E +:10233000034A426707228267C3670120704700BFD4 +:102340003322002007B5052917D8DFE801F0191658 +:1023500003191920302383F31188104A01210190B9 +:10236000FFF7B0FA019802210D4AFFF7ABFA0D48CA +:10237000FFF7CCF9002383F3118803B05DF804FB69 +:10238000302383F311880748FFF796F9F2E73023EB +:1023900083F311880348FFF7ADF9EBE7F841000834 +:1023A0001C420008B026002038B50C4D0C4C2A46C3 +:1023B0000C4904F10800FFF767FF05F1CA0204F1B8 +:1023C00010000949FFF760FF05F5CA7204F1180013 +:1023D0000649BDE83840FFF757BF00BF883F0020DF +:1023E0003C220020D8410008E2410008ED410008ED +:1023F00070B5044608460D46FEF744FDC6B22046B9 +:10240000013403780BB9184670BD32462946FEF7F1 +:1024100025FD0028F3D10120F6E700002DE9F84F53 +:1024200005460C46FEF72EFD2C49C6B22846FFF79E +:10243000DFFF08B10536F6B229492846FFF7D8FF75 +:1024400008B11036F6B2632E0DD8DFF89080DFF8B1 +:102450009090244FDFF894A0DFF894B02E7846B91E +:102460002670BDE8F88F29462046BDE8F84F01F0F8 +:10247000EBBD252E2ED1072241462846FEF7EEFC65 +:1024800070B9DBF8003007350C3444F80C3CDBF84D +:10249000043044F8083CDBF8083044F8043CDDE73D +:1024A000082249462846FEF7D9FC98B9A21C0E4BD3 +:1024B000197802320909C95D02F8041C13F8011BDE +:1024C00001F00F015345C95D02F8031CF0D1183427 +:1024D0000835C3E7013504F8016BBFE7C4420008C3 +:1024E000ED410008D942000800E8F11F0CE8F11F97 +:1024F000CC420008BFF34F8F044B1A695107FCD13F +:10250000D3F810215207F8D1704700BF00200052C5 +:1025100008B50D4B1B78ABB9FFF7ECFF0B4BDA6836 +:10252000D10704D50A4A5A6002F188325A60D3F8BA +:102530000C21D20706D5064AC3F8042102F18832DD +:10254000C3F8042108BD00BFE6410020002000526E +:102550002301674508B5114B1B78F3B9104B1A6975 +:10256000510703D5DA6842F04002DA60D3F810214F +:10257000520705D5D3F80C2142F04002C3F80C21D4 +:10258000FFF7B8FF064BDA6842F00102DA60D3F8D1 +:102590000C2142F00102C3F80C2108BDE6410020E5 +:1025A000002000520F289ABF00F5806040040020F0 +:1025B000704700004FF40030704700001020704753 +:1025C0000F2808B50BD8FFF7EDFF00F500330268C0 +:1025D000013204D104308342F9D1012008BD00202A +:1025E000FCE700000F2838B505463FD8FFF782FF0B +:1025F0001F4CFFF78DFF4FF0FF3307286361C4F8CE +:1026000014311DD82361FFF775FF030243F0240343 +:10261000E360E36843F08003E36023695A07FCD476 +:102620002846FFF767FFFFF7BDFF4FF4003100F0CA +:10263000F5F82846FFF78EFFBDE83840FFF7C0BF2A +:10264000C4F81031FFF756FFA0F108031B0243F056 +:102650002403C4F80C31D4F80C3143F08003C4F8DF +:102660000C31D4F810315B07FBD4D9E7002038BD1A +:10267000002000522DE9F84F05460C46104645EA69 +:102680000203DE0602D00020BDE8F88F20F01F0014 +:10269000DFF8BCB0DFF8BCA0FFF73AFF04EB00089E +:1026A000444503D10120FFF755FFEDE720222946DD +:1026B000204601F0B9FC10B920352034F0E72B4654 +:1026C00005F120021F68791CDDD104339A42F9D14B +:1026D00005F178431B481C4EB3F5801F1B4B38BFD8 +:1026E000184603F1F80332BFD946D1461E46FFF71C +:1026F00001FF0760A5EB040C336804F11C0143F0F3 +:1027000002033360231FD9F8007017F00507FAD1D0 +:1027100053F8042F8B424CF80320F4D1BFF34F8FB2 +:10272000FFF7E8FE4FF0FF332022214603602846E2 +:10273000336823F00203336001F076FC0028BBD03D +:102740003846B0E7142100520C20005214200052E9 +:10275000102000521021005210B5084C237828B1E7 +:102760001BB9FFF7D5FE0123237010BD002BFCD051 +:102770002070BDE81040FFF7EDBE00BFE64100202D +:102780000244074BD2B210B5904200D110BD441C98 +:1027900000B253F8200041F8040BE0B2F4E700BFA8 +:1027A000504000580E4B30B51C6F240405D41C6FEC +:1027B0001C671C6F44F400441C670A4C02442368E5 +:1027C000D2B243F480732360074B904200D130BDF6 +:1027D000441C51F8045B00B243F82050E0B2F4E727 +:1027E00000440258004802585040005807B50122E2 +:1027F00001A90020FFF7C4FF019803B05DF804FBB6 +:1028000013B50446FFF7F2FFA04205D0012201A94B +:1028100000200194FFF7C6FF02B010BD0144BFF3D2 +:102820004F8F064B884204D3BFF34F8FBFF36F8F98 +:102830007047C3F85C022030F4E700BF00ED00E011 +:10284000034B1A681AB9034AD2F8D0241A607047A9 +:10285000E84100200040025808B5FFF7F1FF024BA5 +:102860001868C0F3806008BDE8410020EFF30983D9 +:10287000054968334A6B22F001024A6383F30988F1 +:10288000002383F31188704700EF00E0302080F3CD +:10289000118862B60D4B0E4AD96821F4E061090433 +:1028A000090C0A430B49DA60D3F8FC2042F080722D +:1028B000C3F8FC20084AC2F8B01F116841F00101BA +:1028C00011602022DA7783F82200704700ED00E0E3 +:1028D0000003FA0555CEACC5001000E0302310B55A +:1028E00083F311880E4B5B6813F4006314D0F1EE90 +:1028F000103AEFF309844FF08073683CE361094BB1 +:10290000DB6B236684F30988FFF7BAFA10B1064B34 +:10291000A36110BD054BFBE783F31188F9E700BF06 +:1029200000ED00E000EF00E02F0400083204000892 +:1029300070B5BFF34F8FBFF36F8F1A4A0021C2F8F3 +:102940005012BFF34F8FBFF36F8F536943F40033BF +:102950005361BFF34F8FBFF36F8FC2F88410BFF383 +:102960004F8FD2F8803043F6E074C3F3C900C3F34D +:102970004E335B0103EA0406014646EA81750139DC +:10298000C2F86052F9D2203B13F1200FF2D1BFF30D +:102990004F8F536943F480335361BFF34F8FBFF3BD +:1029A0006F8F70BD00ED00E0FEE70000214B224874 +:1029B000224A70B5904237D3214BC11EDA1C121A3D +:1029C00022F003028B4238BF00220021FEF762FA98 +:1029D0001C4A0023C2F88430BFF34F8FD2F88030F6 +:1029E00043F6E074C3F3C900C3F34E335B0103EA5B +:1029F0000406014646EA81750139C2F86C52F9D2E3 +:102A0000203B13F1200FF2D1BFF34F8FBFF36F8F35 +:102A1000BFF34F8FBFF36F8F0023C2F85032BFF365 +:102A20004F8FBFF36F8F70BD53F8041B40F8041B2A +:102A3000C0E700BFC4440008BC430020BC430020E2 +:102A4000BC43002000ED00E0074BD3F8D81021EA8A +:102A50000001C3F8D810D3F8002122EA0002C3F81D +:102A60000021D3F8003170470044025870B5D0E916 +:102A7000244300224FF0FF359E6804EB42135101BE +:102A8000D3F80009002805DAD3F8000940F08040A7 +:102A9000C3F80009D3F8000B002805DAD3F8000BBF +:102AA00040F08040C3F8000B013263189642C3F82F +:102AB0000859C3F8085BE0D24FF00113C4F81C3882 +:102AC00070BD0000890141F02001016103699B068E +:102AD000FCD41220FFF70CBA10B50A4C2046FEF7C2 +:102AE000CFFE094BC4F89030084BC4F89430084C22 +:102AF0002046FEF7C5FE074BC4F89030064BC4F8DD +:102B0000943010BDEC410020000008401043000844 +:102B100088420020000004401C43000870B5037880 +:102B20000546012B5CD1434BD0F89040984258D1D8 +:102B3000414B0E216520D3F8D82042F00062C3F843 +:102B4000D820D3F8002142F00062C3F80021D3F866 +:102B50000021D3F8802042F00062C3F88020D3F82F +:102B6000802022F00062C3F88020D3F88030FEF786 +:102B7000B3FC324BE360324BC4F800380023D5F885 +:102B80009060C4F8003EC02323604FF40413A36395 +:102B90003369002BFCDA01230C203361FFF7A8F91D +:102BA0003369DB07FCD41220FFF7A2F93369002B4D +:102BB000FCDA00262846A660FFF758FF6B68C4F8C9 +:102BC0001068DB68C4F81468C4F81C6883BB1D4B2C +:102BD000A3614FF0FF336361A36843F00103A36077 +:102BE00070BD194B9842C9D1134B4FF08060D3F898 +:102BF000D82042F00072C3F8D820D3F8002142F068 +:102C00000072C3F80021D3F80021D3F8802042F0ED +:102C10000072C3F88020D3F8802022F00072C3F83D +:102C20008020D3F88030FFF70FFF0E214D209EE764 +:102C3000064BCDE7EC410020004402584014004010 +:102C400003002002003C30C088420020083C30C015 +:102C5000F8B5D0F89040054600214FF000662046B8 +:102C6000FFF730FFD5F8941000234FF001128F6862 +:102C70004FF0FF30C4F83438C4F81C2804EB43127A +:102C800001339F42C2F80069C2F8006BC2F808091C +:102C9000C2F8080BF2D20B68D5F89020C5F898302E +:102CA000636210231361166916F01006FBD112201F +:102CB000FFF71EF9D4F8003823F4FE63C4F8003897 +:102CC000A36943F4402343F01003A3610923C4F82C +:102CD0001038C4F814380B4BEB604FF0C043C4F805 +:102CE000103B094BC4F8003BC4F81069C4F8003924 +:102CF000D5F8983003F1100243F48013C5F89820FA +:102D0000A362F8BDEC42000840800010D0F890208B +:102D100090F88A10D2F8003823F4FE6343EA0113D6 +:102D2000C2F80038704700002DE9F84300EB81033A +:102D3000D0F890500C468046DA680FFA81F94801C5 +:102D4000166806F00306731E022B05EB41134FF0C5 +:102D5000000194BFB604384EC3F8101B4FF00101B8 +:102D600004F1100398BF06F1805601FA03F391694C +:102D700098BF06F5004600293AD0578A04F1580159 +:102D8000374349016F50D5F81C180B430021C5F893 +:102D90001C382B180127C3F81019A7405369611E6E +:102DA0009BB3138A928B9B08012A88BF5343D8F8A0 +:102DB0009820981842EA034301F140022146C8F8DE +:102DC0009800284605EB82025360FFF77BFE08EB74 +:102DD0008900C3681B8A43EA845348341E43640154 +:102DE0002E51D5F81C381F43C5F81C78BDE8F88370 +:102DF00005EB4917D7F8001B21F40041C7F8001B69 +:102E0000D5F81C1821EA0303C0E704F13F030B4A7D +:102E10002846214605EB83035A60FFF753FE05EB76 +:102E20004910D0F8003923F40043C0F80039D5F830 +:102E30001C3823EA0707D7E70080001000040002CF +:102E4000D0F894201268C0F89820FFF70FBE000059 +:102E50005831D0F8903049015B5813F4004004D049 +:102E600013F4001F0CBF0220012070474831D0F836 +:102E7000903049015B5813F4004004D013F4001F54 +:102E80000CBF02200120704700EB8101CB68196A5A +:102E90000B6813604B6853607047000000EB8103C0 +:102EA00030B5DD68AA691368D36019B9402B84BFB7 +:102EB000402313606B8A1468D0F890201C4402EB06 +:102EC0004110013C09B2B4FBF3F46343033323F034 +:102ED000030343EAC44343F0C043C0F8103B2B68EC +:102EE00003F00303012B0ED1D2F8083802EB411096 +:102EF00013F4807FD0F8003B14BF43F0805343F0BD +:102F00000053C0F8003B02EB4112D2F8003B43F003 +:102F10000443C2F8003B30BD2DE9F041D0F8906089 +:102F200005460C4606EB4113D3F8087B3A07C3F875 +:102F3000087B08D5D6F814381B0704D500EB8103AD +:102F4000DB685B689847FA071FD5D6F81438DB07AB +:102F50001BD505EB8403D968CCB98B69488A5A68BC +:102F6000B2FBF0F600FB16228AB91868DA689042C4 +:102F70000DD2121AC3E90024302383F311882146AD +:102F80002846FFF78BFF84F31188BDE8F081012309 +:102F900003FA04F26B8923EA02036B81CB68002BEE +:102FA000F3D021462846BDE8F041184700EB8103E5 +:102FB0004A0170B5DD68D0F890306C692668E6602B +:102FC00056BB1A444FF40020C2F810092A6802F0D8 +:102FD0000302012A0AB20ED1D3F8080803EB421407 +:102FE00010F4807FD4F8000914BF40F0805040F006 +:102FF0000050C4F8000903EB4212D2F8000940F077 +:103000000440C2F800090122D3F8340802FA01F1A1 +:103010000143C3F8341870BD19B9402E84BF402055 +:10302000206020681A442E8A8419013CB4FBF6F40F +:1030300040EAC44040F00050C6E700002DE9F843E4 +:10304000D0F8906005460C464F0106EB4113D3F8CB +:10305000088918F0010FC3F808891CD0D6F8103879 +:10306000DB0718D500EB8103D3F80CC0DCF8143073 +:10307000D3F800E0DA68964530D2A2EB0E024FF0AA +:1030800000091A60C3F80490302383F31188FFF716 +:103090008DFF89F3118818F0800F1DD0D6F83438D1 +:1030A0000126A640334217D005EB84030134D5F83E +:1030B0009050D3F80CC0E4B22F44DCF8142005EB98 +:1030C0000434D2F800E05168714514D3D5F834388F +:1030D00023EA0606C5F83468BDE8F883012303FA3D +:1030E00001F2038923EA02030381DCF80830002B94 +:1030F000D1D09847CFE7AEEB0103BCF81000834274 +:1031000028BF0346D7F8180980B2B3EB800FE3D885 +:103110009068A0F1040959F8048FC4F80080A0EB6E +:1031200009089844B8F1040FF5D818440B4490608E +:103130005360C8E72DE9F84FD0F8905004466E6907 +:10314000AB691E4016F480586E6103D0BDE8F84F9D +:10315000FEF706BC002E12DAD5F8003E9B0705D01C +:10316000D5F8003E23F00303C5F8003ED5F8043837 +:10317000204623F00103C5F80438FEF71FFC37058D +:1031800005D52046FFF772FC2046FEF705FCB0048B +:103190000CD5D5F8083813F0060FEB6823F47053FC +:1031A0000CBF43F4105343F4A053EB6031071BD51D +:1031B0006368DB681BB9AB6923F00803AB61237854 +:1031C000052B0CD1D5F8003E9A0705D0D5F8003E66 +:1031D00023F00303C5F8003E2046FEF7EFFB6368CB +:1031E000DB680BB120469847F30200F1BA80B702C2 +:1031F00026D5D4F8909000274FF0010A09EB47122A +:10320000D2F8003B03F44023B3F5802F11D1D2F85C +:10321000003B002B0DDA62890AFA07F322EA030366 +:10322000638104EB8703DB68DB6813B13946204612 +:1032300098470137D4F89430FFB29B689F42DDD99C +:10324000F00619D5D4F89000026AC2F30A1702F00A +:103250000F0302F4F012B2F5802F00F0CA80B2F52D +:10326000402F09D104EB8303002200F58050DB6876 +:103270001B6A974240F0B0803003D5F8185835D516 +:10328000E90303D500212046FFF746FEAA0303D534 +:1032900001212046FFF740FE6B0303D502212046A3 +:1032A000FFF73AFE2F0303D503212046FFF734FE34 +:1032B000E80203D504212046FFF72EFEA90203D51C +:1032C00005212046FFF728FE6A0203D50621204685 +:1032D000FFF722FE2B0203D507212046FFF71CFE35 +:1032E000EF0103D508212046FFF716FE700340F1D9 +:1032F000A780E90703D500212046FFF79FFEAA0714 +:1033000003D501212046FFF799FE6B0703D5022163 +:103310002046FFF793FE2F0703D503212046FFF732 +:103320008DFEEE0603D504212046FFF787FEA80692 +:1033300003D505212046FFF781FE690603D5062146 +:103340002046FFF77BFE2A0603D507212046FFF71C +:1033500075FEEB0574D520460821BDE8F84FFFF750 +:103360006DBED4F890904FF0000B4FF0010AD4F8E6 +:1033700094305FFA8BF79B689F423FF638AF09EBBA +:103380004713D3F8002902F44022B2F5802F20D150 +:10339000D3F80029002A1CDAD3F8002942F0904221 +:1033A000C3F80029D3F80029002AFBDB3946D4F8FA +:1033B0009000FFF787FB22890AFA07F322EA03034A +:1033C000238104EB8703DB689B6813B139462046F1 +:1033D00098470BF1010BCAE7910701D1D0F80080A3 +:1033E000072A02F101029CBF03F8018B4FEA18285B +:1033F0003FE704EB830300F58050DA68D2F818C089 +:10340000DCF80820DCE9001CA1EB0C0C00218F4249 +:1034100008D1DB689B699A683A449A605A683A44D2 +:103420005A6029E711F0030F01D1D0F800808C45D4 +:1034300001F1010184BF02F8018B4FEA1828E6E789 +:10344000BDE8F88F08B50348FFF774FEBDE80840F3 +:10345000FFF744BAEC41002008B50348FFF76AFEC5 +:10346000BDE80840FFF73ABA88420020D0F8903013 +:1034700003EB4111D1F8003B43F40013C1F8003BCA +:1034800070470000D0F8903003EB4111D1F80039BB +:1034900043F40013C1F8003970470000D0F89030B1 +:1034A00003EB4111D1F8003B23F40013C1F8003BBA +:1034B00070470000D0F8903003EB4111D1F800398B +:1034C00023F40013C1F800397047000030B504330D +:1034D000039C0172002104FB0325C160C0E906536F +:1034E000049B0363059BC0E90000C0E90422C0E916 +:1034F0000842C0E90A11436330BD00000022416A5E +:10350000C260C0E90411C0E90A226FF00101FEF7B0 +:103510005FBD0000D0E90432934201D1C2680AB90C +:10352000181D704700207047036919600021C268A8 +:103530000132C260C269134482699342036124BFAD +:10354000436A0361FEF738BD38B504460D46E368AB +:103550003BB162690020131D1268A3621344E36249 +:1035600007E0237A33B929462046FEF715FD0028E7 +:10357000EDDA38BD6FF00100FBE70000C368C269F7 +:10358000013BC3604369134482699342436124BF92 +:10359000436A436100238362036B03B1184770479A +:1035A00070B53023044683F31188866A3EB9FFF76D +:1035B000CBFF054618B186F31188284670BDA36A73 +:1035C000E26A13F8015B9342A36202D32046FFF73D +:1035D000D5FF002383F31188EFE700002DE9F84FB2 +:1035E00004460E46174698464FF0300989F3118875 +:1035F0000025AA46D4F828B0BBF1000F09D14146F6 +:103600002046FFF7A1FF20B18BF311882846BDE8C3 +:10361000F88FD4E90A12A7EB050B521A934528BF7D +:103620009346BBF1400F1BD9334601F1400251F8DC +:10363000040B914243F8040BF9D1A36A403640359C +:103640004033A362D4E90A239A4202D32046FFF70B +:1036500095FF8AF31188BD42D8D289F31188C9E752 +:1036600030465A46FDF7F0FBA36A5E445D445B4476 +:10367000A362E7E710B5029C0433017203FB042147 +:10368000C460C0E906130023C0E90A33039B036347 +:10369000049BC0E90000C0E90422C0E9084243637A +:1036A00010BD0000026A6FF00101C260426AC0E909 +:1036B00004220022C0E90A22FEF78ABCD0E90423D2 +:1036C0009A4201D1C26822B9184650F8043B0B60F7 +:1036D000704700231846FAE7C3680021C269013326 +:1036E000C3604369134482699342436124BF436AC0 +:1036F0004361FEF761BC000038B504460D46E3683F +:103700003BB1236900201A1DA262E2691344E362FF +:1037100007E0237A33B929462046FEF73DFC00280E +:10372000EDDA38BD6FF00100FBE7000003691960B6 +:10373000C268013AC260C26913448269934203615C +:1037400024BF436A036100238362036B03B11847FC +:103750007047000070B530230D460446114683F3D0 +:103760001188866A2EB9FFF7C7FF10B186F311885A +:1037700070BDA36A1D70A36AE26A01339342A3621B +:1037800004D3E16920460439FFF7D0FF002080F31D +:103790001188EDE72DE9F84F04460D46904699460D +:1037A0004FF0300A8AF311880026B346A76A4FB952 +:1037B00049462046FFF7A0FF20B187F31188304625 +:1037C000BDE8F88FD4E90A073A1AA8EB0607974232 +:1037D00028BF1746402F1BD905F1400355F8042B8D +:1037E0009D4240F8042BF9D1A36A40364033A362CE +:1037F000D4E90A239A4204D3E16920460439FFF749 +:1038000095FF8BF311884645D9D28AF31188CDE70D +:1038100029463A46FDF718FBA36A3D443E443B4423 +:10382000A362E5E7D0E904239A4217D1C3689BB1AC +:10383000836A8BB1043B9B1A0ED01360C368013BB3 +:10384000C360C3691A4483699A42026124BF436A10 +:103850000361002383620123184670470023FBE7BE +:1038600000F024B9014B586A704700BF000C0040BB +:10387000034B002258631A610222DA60704700BFCE +:10388000000C0040014B0022DA607047000C004041 +:10389000014B5863704700BF000C0040FEE700007A +:1038A00070B51B4B0025044686B058600E468562F5 +:1038B0000163FEF7EBFF04F11003A560E562C4E9C4 +:1038C00004334FF0FF33C4E90044C4E90635FFF781 +:1038D000C9FF2B46024604F134012046C4E90823FF +:1038E00080230C4A2565FEF70DFB01230A4AE060A0 +:1038F00000920375684672680192B268CDE90223AE +:10390000064BCDE90435FEF725FB06B070BD00BFC0 +:10391000A8260020284300082D4300089D380008F1 +:10392000024AD36A1843D062704700BF4024002087 +:103930004B6843608B688360CB68C3600B694361ED +:103940004B6903628B6943620B6803607047000038 +:1039500008B53C4B40F2FF713B48D3F888200A433E +:10396000C3F88820D3F8882022F4FF6222F00702EF +:10397000C3F88820D3F88820D3F8E0200A43C3F89E +:10398000E020D3F808210A43C3F808212F4AD3F8CE +:1039900008311146FFF7CCFF00F5806002F11C01F1 +:1039A000FFF7C6FF00F5806002F13801FFF7C0FFA6 +:1039B00000F5806002F15401FFF7BAFF00F5806066 +:1039C00002F17001FFF7B4FF00F5806002F18C0195 +:1039D000FFF7AEFF00F5806002F1A801FFF7A8FF36 +:1039E00000F5806002F1C401FFF7A2FF00F58060DE +:1039F00002F1E001FFF79CFF00F5806002F1FC019D +:103A0000FFF796FF02F58C7100F58060FFF790FFDD +:103A100000F018F90E4BD3F8902242F00102C3F8DF +:103A20009022D3F8942242F00102C3F89422052296 +:103A3000C3F898204FF06052C3F89C20054AC3F8A1 +:103A4000A02008BD0044025800000258344300087A +:103A500000ED00E01F00080308B500F0C7FAFEF70C +:103A60002FFA0F4BD3F8DC2042F04002C3F8DC20E1 +:103A7000D3F8042122F04002C3F80421D3F8043122 +:103A8000084B1A6842F008021A601A6842F00402F1 +:103A90001A60FEF7D5FEBDE80840FEF785BC00BF02 +:103AA000004402580018024870470000114BD3F838 +:103AB000E82042F00802C3F8E820D3F8102142F0D1 +:103AC0000802C3F810210C4AD3F81031D36B43F02D +:103AD0000803D363C722094B9A624FF0FF32DA62C0 +:103AE00000229A615A63DA605A6001225A611A60B0 +:103AF000704700BF004402580010005C000C0040FA +:103B0000094A08B51169D3680B40D9B29B076FEA1F +:103B10000101116107D5302383F31188FEF7E6F91F +:103B2000002383F3118808BD000C0040064BD3F836 +:103B3000DC200243C3F8DC20D3F804211043C3F88F +:103B40000401D3F8043170470044025808B53C4BD7 +:103B50004FF0FF31D3F8802062F00042C3F880209C +:103B6000D3F8802002F00042C3F88020D3F88020F0 +:103B7000D3F88420C3F88410D3F884200022C3F83B +:103B80008420D3F88400D86F40F0FF4040F4FF0059 +:103B900040F4DF4040F07F00D867D86F20F0FF404E +:103BA00020F4FF0020F4DF4020F07F00D867D86FBA +:103BB000D3F888006FEA40506FEA5050C3F888008D +:103BC000D3F88800C0F30A00C3F88800D3F888004F +:103BD000D3F89000C3F89010D3F89000C3F8902069 +:103BE000D3F89000D3F89400C3F89410D3F894005D +:103BF000C3F89420D3F89400D3F89800C3F8981031 +:103C0000D3F89800C3F89820D3F89800D3F88C0024 +:103C1000C3F88C10D3F88C00C3F88C20D3F88C0038 +:103C2000D3F89C00C3F89C10D3F89C10C3F89C20D8 +:103C3000D3F89C30FDF774FBBDE8084000F0AEB946 +:103C40000044025808B50122534BC3F80821534BD6 +:103C5000D3F8F42042F00202C3F8F420D3F81C2178 +:103C600042F00202C3F81C210222D3F81C314C4B53 +:103C7000DA605A689104FCD54A4A1A6001229A60B7 +:103C8000494ADA6000221A614FF440429A61444B7B +:103C90009A699204FCD51A6842F480721A603F4B0C +:103CA0001A6F12F4407F04D04FF480321A6700225A +:103CB0001A671A6842F001021A60384B1A685007F6 +:103CC000FCD500221A611A6912F03802FBD10121D9 +:103CD00019604FF0804159605A67344ADA62344AB9 +:103CE0001A611A6842F480321A602C4B1A689103E8 +:103CF000FCD51A6842F480521A601A689204FCD506 +:103D00002C4A2D499A6200225A63196301F57C01FD +:103D1000DA6301F2E71199635A64284A1A64284A5F +:103D2000DA621A6842F0A8521A601C4B1A6802F054 +:103D30002852B2F1285FF9D148229A614FF4886283 +:103D4000DA6140221A621F4ADA641F4A1A651F4A62 +:103D50005A651F4A9A6532231E4A1360136803F09E +:103D60000F03022BFAD10D4A136943F003031361C9 +:103D7000136903F03803182BFAD14FF00050FFF706 +:103D8000D5FE4FF08040FFF7D1FE4FF00040BDE878 +:103D90000840FFF7CBBE00BF00800051004402582E +:103DA0000048025800C000F0020000010000FF01BE +:103DB000008890081210200063020901470E0508D0 +:103DC000DD0BBF0120000020000001100910E00001 +:103DD00000010110002000524FF0B04208B5D2F8A7 +:103DE000883003F00103C2F8883023B1044A136815 +:103DF0000BB150689847BDE80840FEF76FBD00BFA3 +:103E00003C4300204FF0B04208B5D2F8883003F0B0 +:103E10000203C2F8883023B1044A93680BB1D0681A +:103E20009847BDE80840FEF759BD00BF3C4300205D +:103E30004FF0B04208B5D2F8883003F00403C2F85E +:103E4000883023B1044A13690BB150699847BDE823 +:103E50000840FEF743BD00BF3C4300204FF0B04296 +:103E600008B5D2F8883003F00803C2F8883023B1CF +:103E7000044A93690BB1D0699847BDE80840FEF742 +:103E80002DBD00BF3C4300204FF0B04208B5D2F832 +:103E9000883003F01003C2F8883023B1044A136A53 +:103EA0000BB1506A9847BDE80840FEF717BD00BF48 +:103EB0003C4300204FF0B04310B5D3F8884004F4E1 +:103EC0007872C3F88820A30604D5124A936A0BB10E +:103ED000D06A9847600604D50E4A136B0BB1506B3D +:103EE0009847210604D50B4A936B0BB1D06B9847CA +:103EF000E20504D5074A136C0BB1506C9847A30533 +:103F000004D5044A936C0BB1D06C9847BDE81040BF +:103F1000FEF7E4BC3C4300204FF0B04310B5D3F8AB +:103F2000884004F47C42C3F88820620504D5164A10 +:103F3000136D0BB1506D9847230504D5124A936D4C +:103F40000BB1D06D9847E00404D50F4A136E0BB146 +:103F5000506E9847A10404D50B4A936E0BB1D06EF6 +:103F60009847620404D5084A136F0BB1506F984705 +:103F7000230404D5044A936F0BB1D06F9847BDE872 +:103F80001040FEF7ABBC00BF3C43002008B5FFF774 +:103F9000B7FDBDE80840FEF7A1BC0000062108B54A +:103FA0000846FDF799FA06210720FDF795FA062144 +:103FB0000820FDF791FA06210920FDF78DFA062168 +:103FC0000A20FDF789FA06211720FDF785FA062158 +:103FD0002820FDF781FA09217A20FDF77DFA0721D3 +:103FE0003220BDE80840FDF777BA000008B5FFF7BA +:103FF000ADFD00F00BF8FDF741FCFDF713FBFFF7FB +:1040000053FDBDE80840FFF72BBC00000023054A24 +:1040100019460133102BC2E9001102F10802F8D150 +:10402000704700BF3C43002010B501390244904264 +:1040300001D1002005E0037811F8014FA34201D01F +:10404000181B10BD0130F2E7034611F8012B03F8ED +:10405000012B002AF9D1704753544D333248373F72 +:104060003F3F0053544D3332483733782F3732783F +:104070000053544D3332483734332F3735332F37CD +:104080003530000001105A0003105900012058007B +:1040900003205600100002400800024000080240C1 +:1040A00000000B0028000240080002400408024003 +:1040B00006010C00400002400800024008080240CF +:1040C00010020D0058000240080002400C08024097 +:1040D00016030E00700002400C000240100802405F +:1040E00000040F00880002400C0002401408024047 +:1040F00006051000A00002400C0002401808024013 +:1041000010061100B80002400C0002401C080240DA +:1041100016072F0010040240080402402008024045 +:104120000008380028040240080402402408024025 +:1041300006093900400402400804024028080240F1 +:10414000100A3A0058040240080402402C080240B9 +:10415000160B3B00700402400C0402403008024081 +:10416000000C3C00880402400C0402403408024069 +:10417000060D4400A00402400C040240380802402E +:10418000100E4500B80402400C0402403C080240F6 +:10419000160F460000000000A11500088D1500084C +:1041A000C9150008B5150008C1150008AD150008AF +:1041B0009915000885150008D515000800000000B5 +:1041C000010000000000000063300000C84100084A +:1041D00098240020A82600204172647550696C6FF5 +:1041E000740025424F415244252D424C0025534531 +:1041F0005249414C25000000020000000000000070 +:10420000C11700083118000840004000583F002046 +:10421000683F0020020000000000000003000000D2 +:1042200000000000791800080000000010000000E5 +:10423000783F0020000000000100000000000000A6 +:10424000EC4100200101020045230008552200082E +:10425000F1220008D5220008430000006042000857 +:1042600009024300020100C03209040000010202F9 +:1042700001000524001001052401000104240202AC +:104280000524060001070582030800FF0904010058 +:10429000020A000000070501024000000705810234 +:1042A0004000000012000000AC42000812011001A2 +:1042B0000200004009124157000201020301000000 +:1042C0000403090425424F4152442500426C69749D +:1042D0007A4837343350726F0030313233343536E8 +:1042E0003738394142434445460000000000000091 +:1042F000D51900088D1C0008391D00084000400039 +:104300002443002024430020010000003443002007 +:1043100080000000400100000800000000010000D3 +:1043200000100000080000006D61696E0069646C97 +:10433000650000000000812A00000000AAAAAAAAC5 +:1043400000000024FFFE00000000000000A00A00A2 +:104350000000000100000000AAAAAAAA00000001B3 +:10436000FFFF00000000000000000000000000400F +:1043700000000000AAAAAAAA00000040FFFF000057 +:10438000000000000000000000001000000000001D +:10439000AAAAAAAA00000000FFFF00000000000077 +:1043A000000000000000400000000000AAAAAAAA25 +:1043B00000004000FFFF00000000000000000000BF +:1043C0000000000000000000AAAAAAAA0000000045 +:1043D000FFFF0000000000000000000000000000DF +:1043E00000000000AAAAAAAA00000000FFFF000027 +:1043F00000000000000000000000000000000000BD +:10440000AAAAAAAA00000000FFFF00000000000006 +:10441000000000000000000000000000AAAAAAAAF4 +:1044200000000000FFFF000000000000000000008E +:104430000000000000000000AAAAAAAA00000000D4 +:10444000FFFF00000000000000000000000000006E +:1044500000000000AAAAAAAA00000000FFFF0000B6 +:1044600000000000000000008A04000000000000BE +:1044700000001A0000000000FF0000000000000023 +:104480005840000883040000634000085004000006 +:10449000714000080096000000000800960000002F +:1044A0000008000004000000C042000800000000F6 +:1044B00000000000000000000000000000000000FC +:0444C00000000000F8 +:00000001FF diff --git a/Tools/bootloaders/BlitzMiniF745_bl.bin b/Tools/bootloaders/BlitzMiniF745_bl.bin new file mode 100644 index 0000000000000..1580abc166804 Binary files /dev/null and b/Tools/bootloaders/BlitzMiniF745_bl.bin differ diff --git a/Tools/bootloaders/BlitzMiniF745_bl.hex b/Tools/bootloaders/BlitzMiniF745_bl.hex new file mode 100644 index 0000000000000..10dedd366b2ea --- /dev/null +++ b/Tools/bootloaders/BlitzMiniF745_bl.hex @@ -0,0 +1,930 @@ +:020000040800F2 +:1000000000060120010200080302000803020008A4 +:1000100003020008030200080302000803020008AC +:1000200003020008030200080302000899310008D7 +:10003000030200080302000803020008030200088C +:10004000030200080302000803020008030200087C +:100050000302000803020008413400086934000864 +:1000600091340008B9340008E134000803020008A4 +:10007000030200080302000803020008030200084C +:10008000030200080302000803020008030200083C +:1000900003020008030200080302000809350008F3 +:1000A000030200080302000803020008030200081C +:1000B000DD350008030200080302000803020008FF +:1000C00003020008030200080302000803020008FC +:1000D00003020008030200080302000803020008EC +:1000E0006D3500080302000803020008030200083F +:1000F00003020008030200080302000803020008CC +:1001000003020008030200080302000803020008BB +:1001100003020008030200080302000803020008AB +:10012000030200080302000803020008030200089B +:10013000030200080302000803020008030200088B +:100140000302000803020008030200080D2900084A +:10015000030200080302000803020008030200086B +:10016000030200080302000803020008030200085B +:10017000030200080302000803020008030200084B +:10018000030200080302000803020008030200083B +:10019000030200080302000803020008030200082B +:1001A000030200080302000803020008030200081B +:1001B000030200080302000803020008030200080B +:1001C00003020008030200080302000803020008FB +:1001D00003020008030200080302000803020008EB +:1001E00003020008030200080302000803020008DB +:1001F00003020008030200080302000803020008CB +:1002000002E000F000F8FEE772B6374880F3088895 +:10021000364880F3098836483649086040F20000C5 +:10022000CCF200004EF63471CEF200010860BFF34C +:100230004F8FBFF36F8F40F20000C0F2F0004EF618 +:100240008851CEF200010860BFF34F8FBFF36F8F6C +:100250004FF00000E1EE100A4EF63C71CEF20001C4 +:100260000860062080F31488BFF36F8F01F0A8FFA9 +:1002700002F024FF4FF055301F491B4A91423CBF0A +:1002800041F8040BFAE71D49184A91423CBF41F876 +:10029000040BFAE71A491B4A1B4B9A423EBF51F81E +:1002A000040B42F8040BF8E700201849184A914261 +:1002B0003CBF41F8040BFAE701F0C0FF02F05EFF1B +:1002C000144C154DAC4203DA54F8041B8847F9E787 +:1002D00000F042F8114C124DAC4203DA54F8041B02 +:1002E0008847F9E701F0A8BF00060120002201209D +:1002F0000000000808ED00E00000012000060120D9 +:1003000098390008002201205C220120602201208F +:10031000882E0120000200080002000800020008E8 +:10032000000200082DE9F04F2DED108AC1F80CD025 +:10033000D0F80CD0BDEC108ABDE8F08F002383F319 +:1003400011882846A047002001F0E4FAFEE701F0FA +:100350006DFA00DFFEE7000038B500F011FC01F097 +:10036000EFFE054601F022FF0446C8B90E4B9D4240 +:1003700018D001339D4218BF044641F2883504BFAE +:1003800001240025002001F0E5FE0CB100F076F814 +:1003900000F05EFD284600F0FDF800F06FF8F9E788 +:1003A0000025EFE70546EDE7010007B008B500F0CE +:1003B000B9FBA0F120035842584108BD07B541F2EE +:1003C0001203022101A8ADF8043000F0C9FB03B00C +:1003D0005DF804FB38B572B6302383F3118862B63A +:1003E000174803680BB101F063FB164A1448002359 +:1003F0004FF47A7101F052FB002383F31188124C01 +:10040000236813B12368013B2360636813B16368F9 +:10041000013B63600D4D2B7833B963687BB90220D3 +:1004200000F080FC322363602B78032B07D16368D4 +:100430002BB9022000F076FC4FF47A73636038BD6C +:1004400060220120D50300088023012078220120AA +:10045000084B187003280CD8DFE800F008050208E4 +:10046000022000F055BC022000F048BC024B0022E4 +:100470005A6070477822012080230120F8B5404B54 +:10048000404A1C461968013179D004339342F9D1AE +:100490006268A24273D33C4B9B6803F1006303F58F +:1004A000C0339A426BD2002000F084FB0220FFF799 +:1004B000CFFF364B00211A6C19641A6E19661A6E3A +:1004C0005A6C59645A6E59665A6E5A6942F08002E3 +:1004D0005A615A6922F080025A615A691A6942F0D7 +:1004E00000521A611A6922F000521A611B6972B631 +:1004F0004FF0E023C3F8084DD4E90004BFF34F8F59 +:10050000BFF36F8F224AC2F88410BFF34F8F536935 +:1005100023F480335361BFF34F8FD2F88030C3F39D +:10052000C905C3F34E335B0143F6E07603EA060CDC +:1005300029464CEA81770139C2F87472F9D2203B1E +:1005400013F1200FF2D1BFF34F8FBFF36F8FBFF3C3 +:100550004F8FBFF36F8F536923F400335361002330 +:10056000C2F85032BFF34F8FBFF36F8F72B6302394 +:1005700083F3118862B6854680F308882047F8BD6A +:10058000008001082080010800220120003802407C +:1005900000ED00E02DE9F04F93B0B64B0090202223 +:1005A000FF210AA89D6800F0FDFBB34A1378B3B998 +:1005B000B24801211170036072B6302383F31188B1 +:1005C00062B603680BB101F073FAAD4AAB48002381 +:1005D0004FF47A7101F062FA002383F31188009BD3 +:1005E00013B1A84B009A1A60A74A009C1378032BFA +:1005F0001EBF00231370A34A4FF0000A18BF5360B8 +:10060000D3465646D146012000F082FB24B19D4BD3 +:100610001B68002B00F02782002000F083FA039073 +:10062000039B002BF2DB012000F068FB039B213BC6 +:100630001F2BE8D801A252F823F000BFBD06000826 +:10064000E506000879070008070600080706000805 +:10065000070600080B080008DB090008F508000879 +:10066000570900087F090008A509000807060008C7 +:10067000B709000807060008290A00085D070008F6 +:10068000070600086D0A0008C90600085D07000893 +:1006900007060008570900080706000807060008B3 +:1006A00007060008070600080706000807060008F6 +:1006B0000706000807060008790700080220FFF770 +:1006C00075FE002840F0F981009B0221BAF1000F6D +:1006D00008BF1C4605A841F21233ADF8143000F0F3 +:1006E0003FFA90E74FF47A7000F01CFA071EEBDB3C +:1006F0000220FFF75BFE0028E6D0013F052F00F245 +:10070000DE81DFE807F0030A0D1013360523059399 +:10071000042105A800F024FA17E056480421F9E75F +:100720005A480421F6E75A480421F3E74FF01C0821 +:10073000404600F041FA08F104080590042105A89C +:1007400000F00EFAB8F12C0FF2D1012000FA07F7F1 +:1007500047EA0B0B5FFA8BFB4FF0000900F06EFBD2 +:1007600026B10BF00B030B2B08BF0024FFF726FE6E +:1007700049E748480421CDE7002EA5D00BF00B0334 +:100780000B2BA1D10220FFF711FE074600289BD0BA +:10079000012000F00FFA0220FFF75AFE00261FFA90 +:1007A00086F8404600F016FA0446B0B10399A1F16C +:1007B000400251425141404600F01CFA01360028E7 +:1007C000EDD1BA46044641F21213022105A8ADF854 +:1007D00014303E4600F0C4F915E70120FFF738FE5B +:1007E0002546244B9B68AB4207D9284600F0E4F924 +:1007F000013040F067810435F3E7234B00251D707D +:10080000204BBA465D603E46A8E7002E3FF45CAF41 +:100810000BF00B030B2B7FF457AF0220FFF718FEF2 +:10082000322000F07FF9B0F10008FFF64DAF18F06C +:1008300003077FF449AF0F4A926808EB0503934220 +:100840003FF642AFB8F5807F3FF73EAF124B0193C2 +:10085000B84523DD4FF47A7000F064F90390039AF1 +:10086000002AFFF631AF019B039A03F8012B0137F1 +:10087000EDE700BF002201207C230120602201203F +:10088000D5030008802301207822012004220120C2 +:10089000082201200C2201207C220120C820FFF721 +:1008A00085FD074600283FF40FAF1F2D11D8C5F175 +:1008B000200242450AAB25F0030028BF4246834987 +:1008C0000192184400F048FA019A8048FF2100F094 +:1008D00069FA4FEAA8037D490193C8F387022846C5 +:1008E00000F068FA064600283FF46DAF019B05EB67 +:1008F000830533E70220FFF759FD00283FF4E4AEFB +:1009000000F0A4F900283FF4DFAE0027B846704B92 +:100910009B68BB4218D91F2F11D80A9B01330ED0F8 +:1009200027F0030312AA134453F8203C05934046D2 +:10093000042205A900F0B6FA04378046E7E73846F6 +:1009400000F03AF90590F2E7CDF81480042105A8EB +:1009500000F006F902E70023642104A8049300F0E4 +:10096000F5F800287FF4B0AE0220FFF71FFD002845 +:100970003FF4AAAE049800F051F90590E6E7002391 +:10098000642104A8049300F0E1F800287FF49CAEF1 +:100990000220FFF70BFD00283FF496AE049800F00C +:1009A0004DF9EAE70220FFF701FD00283FF48CAE85 +:1009B00000F05CF9E1E70220FFF7F8FC00283FF4C3 +:1009C00083AE05A9142000F057F9042107460490CE +:1009D00004A800F0C5F83946B9E7322000F0A2F8C3 +:1009E000071EFFF671AEBB077FF46EAE384A926801 +:1009F00007EB090393423FF667AE0220FFF7D6FCF0 +:100A000000283FF461AE27F003074F44B9453FF497 +:100A1000A5AE484600F0D0F80421059005A800F0E6 +:100A20009FF809F10409F1E74FF47A70FFF7BEFC73 +:100A300000283FF449AE00F009F9002844D00A9B91 +:100A400001330BD008220AA9002000F0B3F90028D6 +:100A50003AD02022FF210AA800F0A4F9FFF7AEFC4B +:100A60001C4800F05FFF13B0BDE8F08F002E3FF48C +:100A70002BAE0BF00B030B2B7FF426AE002364216F +:100A800005A8059300F062F8074600287FF41CAE25 +:100A90000220FFF78BFC804600283FF415AEFFF7DD +:100AA0008DFC41F2883000F03DFF059800F0F8F928 +:100AB000464600F0C3F93C46A5E506464EE64FF033 +:100AC000000901E6BA467EE637467CE67C22012034 +:100AD00000220120A086010070B50F4B1B78013366 +:100AE000DBB2012B0C4611D80C4D29684FF47A73F8 +:100AF0000E6AA2FB0332014622462846B0478442D2 +:100B000004D1074B00221A70012070BD4FF4FA7017 +:100B100000F008FF0020F8E710220120282601201D +:100B2000B423012007B50023024601210DF107007F +:100B30008DF80730FFF7D0FF20B19DF8070003B014 +:100B40005DF804FB4FF0FF30F9E700000A4608B5F6 +:100B50000421FFF7C1FF80F00100C0B2404208BD90 +:100B600030B4054C2368DD69044B0A46AC460146A7 +:100B7000204630BC604700BF28260120A086010027 +:100B800070B501F0E3F9094E094D30800024286862 +:100B90003388834208D901F0D3F92B680444013328 +:100BA000B4F5C03F2B60F2D370BD00BFB623012067 +:100BB0008823012001F078BA00F1006000F5C03010 +:100BC0000068704700F10060920000F5C03001F04D +:100BD00003BA0000054B1A68054B1B889B1A834219 +:100BE00002D9104401F0ACB90020704788230120DD +:100BF000B623012038B5084D044629B128682044A1 +:100C0000BDE8384001F0BCB92868204401F0A0F9E3 +:100C10000028F3D038BD00BF8823012010F0030363 +:100C200009D1B0F5846F04D200F10050A0F5712015 +:100C30000368184670470023FBE7000000F10050EE +:100C4000A0F57120D0F8200470470000064991F803 +:100C5000243033B10023086A81F824300822FFF7DA +:100C6000B1BF0120704700BF8C230120014B1868E1 +:100C7000704700BF002004E0F0B51E4B1D6801382E +:100C80002E0C0A181C48C5F30B04032335460788AD +:100C9000A7420BD144680B46013C934218461BD235 +:100CA00014F9010F48B103F8010BF6E7013B00F11D +:100CB0000800ECD191420ED20B4618462C24B6F512 +:100CC000805F00F8014B0AD1824202D94122981C70 +:100CD0005A70401AF0BD0846B6F5805FF9D041F26F +:100CE00001039D42F5D18242F3D95A2300F8013B1A +:100CF000EFE700BF002004E014220120022802BF19 +:100D0000024B4FF000729A61704700BF000802402A +:100D1000022802BF024B4FF400729A61704700BF75 +:100D200000080240022801BF024A536983F400739D +:100D3000536170470008024070B504464FF47A765C +:100D40004CB1412C254628BF412506FB05F000F09B +:100D5000E9FD641BF4E770BD10B50023934203D096 +:100D6000CC5CC4540133F9E710BD000010B5013864 +:100D700010F9013F3BB191F900409C4203D11AB1F7 +:100D80000131013AF4E71AB191F90020981A10BD27 +:100D90001046FCE703460246D01A12F9011B00294F +:100DA000FAD1704702440346934202D003F8011B74 +:100DB000FAE770472DE9F8431F4D144695F82420B3 +:100DC0000746884652BBDFF870909CB395F82430F4 +:100DD0002BB92022FF2148462F62FFF7E3FF95F849 +:100DE0002400C0F10802A24228BF2246D6B24146E2 +:100DF000920005EB8000FFF7AFFF95F82430A41BAD +:100E00001E44F6B2082E17449044E4B285F82460DC +:100E1000DBD1FFF71BFF0028D7D108E02B6A03EBDB +:100E200082038342CFD0FFF711FF0028CBD10020EF +:100E3000BDE8F8830120FBE78C230120024B1A78E0 +:100E4000024B1A70704700BFB4230120102201200A +:100E500010B5104C104800F0BBF821460E4800F0C9 +:100E6000E3F82468E26ED2F8043843F00203C2F8D3 +:100E700004384FF47A70FFF75FFF0849204600F00E +:100E8000E1F9E26ED2F8043823F00203C2F8043824 +:100E900010BD00BF58370008282601206037000821 +:100EA0007047000030B5094D0A4491420DD011F849 +:100EB000013B5840082340F30004013B2C4013F051 +:100EC000FF0384EA5000F6D1EFE730BD2083B8ED90 +:100ED00072B6302383F3118862B6704702684368A4 +:100EE0001143016003B118477047000013B5446B0C +:100EF000D4F894341A681178042915D1217C022978 +:100F000012D11979128901238B4013420CD101A906 +:100F100004F14C0001F090FFD4F89444019B217936 +:100F20000246206800F0DAF902B010BD143001F07A +:100F300015BF00004FF0FF33143001F00FBF000069 +:100F40004C3001F0E5BF00004FF0FF334C3001F0B2 +:100F5000DFBF0000143001F0E5BE00004FF0FF31AC +:100F6000143001F0DFBE00004C3001F0B1BF0000D2 +:100F70004FF0FF324C3001F0ABBF00000020704753 +:100F800010B5D0F894341A6811780429044617D1A2 +:100F9000017C022914D15979528901238B401342D3 +:100FA0000ED1143001F078FE024648B1D4F89444D2 +:100FB0004FF4807361792068BDE8104000F07CB97F +:100FC00010BD0000406BFFF7DBBF00007047000062 +:100FD0007FB5124B036000234360C0E90233012553 +:100FE00002260F4B057404460290019300F184021F +:100FF000294600964FF48073143001F029FE094B06 +:101000000294CDE9006304F523724FF480732946FE +:1010100004F14C0001F0ECFE04B070BDAC360008E9 +:10102000C50F0008ED0E000808B50A68FFF750FF6D +:101030000B7902EB830318624B790D3342F82300DE +:101040008B7913B102EB830210620223C0F894146F +:101050000374002080F3118808BD000038B5037FB9 +:10106000044613B190F85430ABB9201D012502217C +:10107000FFF734FF04F1140025776FF0010100F051 +:1010800079FC84F8545004F14C006FF00101BDE884 +:10109000384000F06FBC38BD10B501210446043063 +:1010A000FFF71CFF0023237784F8543010BD0000A5 +:1010B00038B504460025143001F0E2FD04F14C007F +:1010C000257701F0ADFE201D84F854500121FFF773 +:1010D00005FF2046BDE83840FFF752BF90F85C306E +:1010E00003F06003202B07D190F85D20212A4FF0F8 +:1010F000000303D81F2A06D800207047222AFBD1FC +:10110000C0E9143303E0034A0265072242658365A0 +:10111000012070472C22012037B5D0F894341A688A +:101120001178042904461AD1017C022917D11979B2 +:10113000128901238B40134211D100F14C0528463E +:1011400001F02CFF58B101A9284601F075FED4F832 +:101150009444019B21790246206800F0BFF803B057 +:1011600030BD0000F0B500EB810385B01E6A044677 +:101170000D46F6B104EB8507301D0821FFF7A8FEE8 +:10118000FFF7ACFEFB685B691B6806F14C001BB106 +:10119000019001F05FFE019803A901F04DFE0246A7 +:1011A00048B1039B2946204600F098F8002383F3BA +:1011B000118805B0F0BDFB685A691268002AF5D0A5 +:1011C0001B8A013B1340F1D104F15C02EAE7000005 +:1011D0000D3138B550F82140D4B1FFF779FED4F87D +:1011E00094241368527903EB8203DB689B695D6882 +:1011F00045B104216018FFF771FE294604F114007F +:1012000001F054FD2046FFF7BBFE002383F3118855 +:1012100038BD00007047000072B6302383F3118898 +:1012200062B6704701F08EB810B50123044628223B +:1012300000F8243B0021FFF7B5FD0023C4E901338A +:1012400010BD000038B50025FFF7E6FF0446C0E9F1 +:101250000355C0E90555C0E90755416001F082F822 +:101260000223237085F31188284638BD70B500EB42 +:10127000810305465069DA600E46144618B1102203 +:101280000021FFF78FFDA06918B110220021FFF7A0 +:1012900089FD31462846BDE8704001F02DB90000B7 +:1012A000826802F0011282600022C0E90422C0E9D3 +:1012B0000622026201F0ACB9F0B400EB8104478968 +:1012C000E4680125A4698D403D43458123600023E6 +:1012D000A2606360F0BC01F0C7B90000F0B400EB9D +:1012E00081040789E468012564698D403D430581D7 +:1012F00023600023A2606360F0BC01F043BA0000E9 +:1013000070B50223002504460370C0E90255C0E908 +:101310000455C0E906554566056280F84C5001F059 +:1013200087F863681B6823B129462046BDE87040F2 +:10133000184770BD0378052B10B504460AD080F815 +:1013400068300523037043681B680BB1042198477C +:101350000023A36010BD00000178052906D190F894 +:101360006820436802701B6803B11847704700008B +:1013700070B590F84C30044613B1002380F84C301F +:1013800004F15C02204601F065F963689B68B3B91B +:1013900094F85C3013F0600533D00021204601F052 +:1013A0001DFC0021204601F00FFC63681B6813B18F +:1013B000062120469847062384F84C3070BD20460D +:1013C00098470028E4D0B4F86230626D9A4288BF32 +:1013D000636594F95C30656D002B80F20281002D0D +:1013E00000F0F180092384F84C30FFF715FF00214D +:1013F000D4E914232046FFF771FF002383F31188FB +:10140000DCE794F85D2003F07F0343EA022340F217 +:101410000232934200F0C48021D8B3F5807F48D0D7 +:101420000DD8012B3FD0022B00F09280002BB4D1BD +:1014300004F16402226502226265A365C3E7B3F585 +:10144000817F00F09A80B3F5407FA6D194F85E309A +:10145000012BA2D1B4F8643043F0020332E0B3F5BB +:10146000006F4DD017D8B3F5A06F31D0A3F5C0638E +:10147000012B92D8636894F85E205E6894F85F1040 +:10148000B4F860302046B047002886D04368236512 +:10149000036863651AE0B3F5106F36D040F6024278 +:1014A00093427FF47AAF5B4B23650223636500238D +:1014B000C3E794F85E30012B7FF46FAFB4F864306B +:1014C00023F00203C4E91455A4F86430A5657AE753 +:1014D000B4F85C30B3F5A06F0ED194F85E3084F8A8 +:1014E0006630204600F0FCFF63681B6813B10121E1 +:1014F00020469847032323700023C4E914339CE754 +:1015000004F1670323650123C3E72378042B0FD17C +:101510002046FFF781FEFFF7C3FE85F31188032104 +:10152000636884F8675021701B680BB120469847A8 +:1015300094F85E30002BDFD084F8673004232370EA +:1015400063681B68002BD7D0022120469847D3E759 +:1015500094F860301D0603F00F0120460AD501F013 +:101560006BF8012804D002287FF417AF2A4B9BE7C1 +:101570002A4B99E701F052F8F3E794F85E30002B1C +:101580007FF40BAF94F8603013F00F01B4D01A065B +:10159000204602D501F036FBAEE701F029FBABE7B0 +:1015A00094F85E30002B7FF4F8AE94F8603013F0BE +:1015B0000F01A1D01B06204602D501F00FFB9BE7CF +:1015C00001F002FB98E7142384F84C30FFF724FE67 +:1015D0002A462B4629462046FFF76EFE85F31188E2 +:1015E000ECE65DB1152384F84C30FFF715FE0021C1 +:1015F000D4E914232046FFF75FFEFEE60B2384F8B0 +:101600004C30FFF709FE2A462B4629462046FFF7B5 +:1016100065FEE3E7DC360008D4360008D83600085B +:1016200038B590F84C300446002B3CD0063BDAB27B +:101630000F2A32D80F2B30D8DFE803F0352F2F08D0 +:1016400021302F2F2F2F2F2F2F2F3535456DB0F80D +:1016500062309D4213D2C3681B8AB5FBF3F203FBD1 +:10166000125565B9FFF7D8FD2A462B462946FFF7E4 +:1016700035FE85F311880A2384F84C300DE01423DD +:1016800084F84C30FFF7C8FD00231A46194620465F +:10169000FFF712FE002383F3118838BD836D03B179 +:1016A00098470023E8E70021204601F097FA00213F +:1016B000204601F089FA63681B6813B106212046B1 +:1016C00098470623D8E7000010B590F84C30142B4B +:1016D000044628D017D8062B05D001D81BB110BD61 +:1016E000093B022BFBD80021204601F077FA0021AC +:1016F000204601F069FA63681B6813B10621204691 +:101700009847062318E0152BE9D10B2380F84C30BD +:10171000FFF782FD00231A461946FFF7DFFD00237D +:1017200083F31188DBE7C3689B695B68002BD6D124 +:10173000836D03B19847002384F84C30CFE7000055 +:1017400000230375826803691B6899689142FBD284 +:101750005A68036042601060586070470023037548 +:10176000826803691B6899689142FBD85A680360D4 +:10177000426010605860704708B5084672B6302362 +:1017800083F3118862B60B7D032B05D0042B0DD09B +:101790002BB983F3118808BD8B6900221A604FF0C2 +:1017A000FF338361FFF7CCFF0023F2E7D1E900327A +:1017B00013605A60F3E70000FFF7C2BF054BD9681A +:1017C0000875186802681A60536001220275D860B3 +:1017D000FEF7A8BDB823012030B50C4BDD684B1CCB +:1017E00087B004460FD02B46094A684600F056F9E8 +:1017F0002046FFF7E3FF009B13B1684600F058F95D +:10180000A86907B030BDFFF7D9FFF9E7B823012079 +:1018100079170008044B1A68DB6890689B68984247 +:1018200094BF002001207047B8230120084B10B559 +:101830001C68D86822681A60536001222275DC6037 +:10184000FFF78CFF01462046BDE81040FEF76ABD59 +:10185000B823012038B5074C074908480123002563 +:101860002370656001F0D2FB0223237085F3118899 +:1018700038BD00BF20260120E4360008B82301202F +:1018800000F04CB9034A516853685B1A9842FBD880 +:10189000704700BF001000E072B6302383F3118858 +:1018A00062B670478B60022308618B8208467047DE +:1018B0008368A3F1840243F8142C026943F8442C92 +:1018C000426943F8402C094A43F8242CC26843F883 +:1018D000182C022203F80C2C002203F80B2C044ACB +:1018E00043F8102CA3F12000704700BF3D0300080F +:1018F000B823012008B5FFF7DBFFBDE80840FFF77C +:101900005BBF0000024BDB6898610F20FFF756BFFA +:10191000B823012008B5FFF7BFFFBDE80840FFF777 +:10192000F1BF000008B501460820FFF7B5FFFFF73B +:1019300053FF002383F3118808BD0000064BDB68CA +:1019400039B1426818605A60136043600420FFF7A1 +:1019500043BF4FF0FF307047B8230120036898421F +:1019600006D01A680260506099611846FFF724BFDC +:101970007047000038B504460D462068844200D107 +:1019800038BD036823605C608561FFF715FFF4E7ED +:1019900010B503689C68A2420CD85C688A600B6032 +:1019A0004C602160596099688A1A9A604FF0FF3341 +:1019B000836010BD1B68121BECE700000A2938BFCA +:1019C0000A2170B504460D460A26601901F018FB7D +:1019D00001F004FB041BA54203D8751C2E460446E7 +:1019E000F3E70A2E04D9BDE87040012001F04EBB98 +:1019F00070BD0000F8B5144B0D46D96103F110011C +:101A000041600A2A1969826038BF0A220160486071 +:101A10001861A818144601F0E5FA0A2701F0DEFA69 +:101A2000431BA342064606D37C1C281901F0E8FAA2 +:101A300027463546F2E70A2F04D9BDE8F8400120D1 +:101A400001F024BBF8BD00BFB8230120F8B506465D +:101A50000D4601F0C3FA0F4A134653F8107F9F4218 +:101A600006D12A4601463046BDE8F840FFF7C2BF1E +:101A7000D169BB68441A2C1928BF2C46A34202D94D +:101A80002946FFF79BFF224631460348BDE8F84050 +:101A9000FFF77EBFB8230120C823012010B4C0E99E +:101AA000032300235DF8044B4361FFF7CFBF000021 +:101AB00010B5194C236998420DD0D0E900328168E5 +:101AC00013605A609A680A449A60002303604FF0DA +:101AD000FF33A36110BD2346026843F8102F536003 +:101AE0000022026022699A4203D1BDE8104001F051 +:101AF00081BA936881680B44936001F06FFA2269A0 +:101B0000E1699268441AA242E4D91144BDE8104048 +:101B1000091AFFF753BF00BFB82301202DE9F04792 +:101B2000DFF8C08008F110072D4ED8F8105001F0F2 +:101B300055FAD8F81C40AA68031B9A4240D81444AE +:101B4000D5E900324FF00009C8F81C4013605A6014 +:101B5000C5F80090D8F81030B34201D101F04AFA2C +:101B600089F31188D5E903312846984772B63023A6 +:101B700083F3118862B66B69002BD6D001F02EFA80 +:101B80006A69A0EB04094A4582460DD2022001F0A1 +:101B90007DFA0022D8F81030B34208D151462846C9 +:101BA000BDE8F047FFF726BF121A2244F2E712EB16 +:101BB000090938BF4A4629463846FFF7E9FEB3E728 +:101BC000D8F81030B34208D01444211AC8F81C00C9 +:101BD000A960BDE8F047FFF7F1BEBDE8F08700BFA0 +:101BE000C8230120B823012000207047FEE7000031 +:101BF000704700004FF0FF307047000072B630238E +:101C000083F3118862B6704702290CD0032904D0EF +:101C10000129074818BF00207047032A05D8054846 +:101C200000EBC2007047044870470020704700BFB7 +:101C3000BC3700083C2201207037000870B59AB00C +:101C40000546084601A9144600F0BEF801A8FFF7B2 +:101C5000A1F8431C5B00C5E9003400222370032374 +:101C60006370C6B201AB02341046D1B28E4204F1A9 +:101C7000020401D81AB070BD13F8011B04F8021C4D +:101C800004F8010C0132F0E708B50448FFF7B6FF8D +:101C9000FFF742FA002383F3118808BD28260120AC +:101CA00090F85C3003F01F02012A07D190F85D2004 +:101CB0000B2A03D10023C0E9143315E003F06003BD +:101CC000202B08D1B0F860302BB990F85D20212A84 +:101CD00003D81F2A04D8FFF701BA222AEBD0FAE76B +:101CE000034A02650722426583650120704700BFF1 +:101CF0003322012007B5052916D8DFE801F01815B1 +:101D00000318181E104A0121FFF778FF0190FFF712 +:101D1000ADFA01980D4A0221FFF7A8FA0C48FFF727 +:101D2000C7F9002383F3118803B05DF804FB08486A +:101D3000FFF764FFFFF792F9F3E70548FFF75EFF4F +:101D4000FFF7AAF9EDE700BF1037000834370008A5 +:101D50002826012038B50C4D0C4C0D492A4604F1BB +:101D60000800FFF76BFF05F1CA0204F110000949F2 +:101D7000FFF764FF05F5CA7204F118000649BDE8D3 +:101D80003840FFF75BBF00BFF02A01203C22012052 +:101D9000F0360008FA3600080537000870B504462A +:101DA00008460D46FEF7F6FFC6B22046013403781A +:101DB0000BB9184670BD32462946FEF7D7FF0028FA +:101DC000F3D10120F6E700002DE9F04705460C4667 +:101DD000FEF7E0FF2B49C6B22846FFF7DFFF08B148 +:101DE0000636F6B228492846FFF7D8FF08B1103664 +:101DF000F6B2632E0BD8DFF88C80DFF88C90234F7F +:101E0000DFF894A02E7846B92670BDE8F087294601 +:101E10002046BDE8F04701F02BBC252E2ED107222D +:101E200041462846FEF7A2FF70B9194B224603F13E +:101E30000C0153F8040B42F8040B8B42F9D11B78C8 +:101E4000137007350D34DDE7082249462846FEF7B2 +:101E50008DFF98B90F4BA21C197809090232C95D90 +:101E600002F8041C13F8011B01F00F015345C95D72 +:101E700002F8031CF0D118340835C3E704F8016BED +:101E80000135BFE7DC37000805370008F2370008E6 +:101E9000E437000820F4F01F2CF4F01FBFF34F8F3D +:101EA000024AD368DB03FCD4704700BF003C024009 +:101EB00008B5074B1B7853B9FFF7F0FF054B1A69BC +:101EC000002ABFBF044A5A6002F188325A6008BD36 +:101ED0004E2D0120003C02402301674508B5054B0B +:101EE0001B7833B9FFF7DAFF034A136943F0004365 +:101EF000136108BD4E2D0120003C02400728F0B5BB +:101F000016D80C4C0C4923787BB90C4D0E4608238F +:101F10004FF0006255F8047B46F8042B013B13F0A8 +:101F2000FF033A44F6D10123237051F82000F0BD9D +:101F30000020FCE7702D0120502D012004380008FE +:101F4000014B53F820007047043800080820704700 +:101F5000072810B5044601D9002010BDFFF7CEFFB9 +:101F6000064B53F824301844C21A0BB90120F4E789 +:101F700012680132F0D1043BF6E700BF04380008D4 +:101F8000072810B5044621D8FFF788FFFFF790FF18 +:101F90000F4AF323D360C300DBB243F4007343F072 +:101FA00002031361136943F480331361FFF776FF73 +:101FB000FFF7A4FF074B53F8241000F0D9F8FFF700 +:101FC0008DFF2046BDE81040FFF7C2BF002010BDC6 +:101FD000003C024004380008F8B512F00103144632 +:101FE00042D18218B2F1016F57D82D4B1B6813F004 +:101FF000010352D02B4DFFF75BFFF323EB60FFF79C +:102000004DFF40F20127032C15D824F00104661877 +:10201000244C401A40F20117B142236900EB01053C +:1020200024D123F001032361FFF758FF0120F8BDFD +:10203000043C0430E7E78307E7D12B6923F44073BE +:102040002B612B693B432B6151F8046B0660BFF396 +:102050004F8FFFF723FF03689E42E9D02B6923F0DF +:1020600001032B61FFF73AFF0020E0E723F4407300 +:10207000236123693B4323610B882B80BFF34F8F80 +:10208000FFF70CFF2D8831F8023BADB2AB42C3D055 +:10209000236923F001032361E4E71846C7E700BF83 +:1020A00000380240003C0240084908B50B7828B1CE +:1020B0001BB9FFF7FDFE01230B7008BD002BFCD000 +:1020C000BDE808400870FFF709BF00BF4E2D012092 +:1020D00010B50244064BD2B2904200D110BD441C50 +:1020E00000B253F8200041F8040BE0B2F4E700BF5F +:1020F000502800400F4B30B51C6F240407D41C6FD0 +:1021000044F400741C671C6F44F400441C670A4CC0 +:10211000236843F4807323600244084BD2B2904298 +:1021200000D130BD441C00B251F8045B43F820508C +:10213000E0B2F4E700380240007000405028004050 +:1021400007B5012201A90020FFF7C2FF019803B0E3 +:102150005DF804FB13B50446FFF7F2FFA04205D07B +:10216000012201A900200194FFF7C4FF02B010BDB5 +:102170000144BFF34F8F064B884204D3BFF34F8F08 +:10218000BFF36F8F7047C3F85C022030F4E700BFE5 +:1021900000ED00E0034B1A681AB9034AD2F874281C +:1021A0001A607047742D01200030024008B5FFF717 +:1021B000F1FF024B1868C0F3407008BD742D012078 +:1021C00070B5BFF34F8FBFF36F8F1A4A0021C2F86B +:1021D0005012BFF34F8FBFF36F8F536943F4003337 +:1021E0005361BFF34F8FBFF36F8FC2F88410BFF3FB +:1021F0004F8FD2F88030C3F3C900C3F34E335B0175 +:1022000043F6E07403EA0406014646EA81750139A3 +:10221000C2F86052F9D2203B13F1200FF2D1BFF384 +:102220004F8F536943F480335361BFF34F8FBFF334 +:102230006F8F70BD00ED00E0FEE7000070B5214B30 +:102240002148224A904237D3214BDA1C121AC11E70 +:1022500022F003028B4238BF00220021FEF7A2FDCC +:102260001C4A0023C2F88430BFF34F8FD2F880306D +:10227000C3F3C900C3F34E335B0143F6E07403EAD2 +:102280000406014646EA81750139C2F86C52F9D25A +:10229000203B13F1200FF2D1BFF34F8FBFF36F8FAD +:1022A000BFF34F8FBFF36F8F0023C2F85032BFF3DD +:1022B0004F8FBFF36F8F70BD53F8041B40F8041BA2 +:1022C000C0E700BFF4390008882E0120882E0120C5 +:1022D000882E012000ED00E070B5D0E91B439E6818 +:1022E00000224FF0FF3504EB42135101D3F80009EF +:1022F0000028BEBFD3F8000940F08040C3F80009B1 +:10230000D3F8000B0028BEBFD3F8000B40F080408C +:10231000C3F8000B013263189642C3F80859C3F89A +:10232000085BE0D24FF00113C4F81C3870BD000008 +:10233000890141F02001016103699B06FCD4122050 +:10234000FFF7A0BA10B5054C2046FEF76DFF4FF021 +:10235000A043E366024B236710BD00BF782D012028 +:102360004838000870B50378012B054650D12A4B38 +:10237000C46E98421BD1294B5A6B42F080025A63BB +:102380005A6D42F080025A655A6D5A6942F08002D5 +:102390005A615A6922F080025A610E2143205B691A +:1023A00000F03AFC1E4BE3601E4BC4F800380023DB +:1023B000C4F8003EC0232360EE6E4FF40413A36301 +:1023C0003369002BFCDA012333610C20FFF75AFA42 +:1023D0003369DB07FCD41220FFF754FA3369002B72 +:1023E000FCDA0026A6602846FFF776FF6B68C4F883 +:1023F0001068DB68C4F81468C4F81C684BB90A4B51 +:10240000A3614FF0FF336361A36843F00103A3604E +:1024100070BD064BF4E700BF782D01200038024064 +:102420004014004003002002003C30C0083C30C093 +:10243000F8B5C46E054600212046FFF779FF296FE5 +:1024400000234FF001128F68C4F834384FF0006653 +:10245000C4F81C284FF0FF3004EB431201339F42B5 +:10246000C2F80069C2F8006BC2F80809C2F8080B8C +:10247000F2D20B68EA6E6B67636210231361166910 +:1024800016F01006FBD11220FFF7FCF9D4F8003843 +:1024900023F4FE63C4F80038A36943F4402343F0F7 +:1024A0001003A3610923C4F81038C4F814380A4B88 +:1024B000EB604FF0C043C4F8103B084BC4F8003B3E +:1024C000C4F81069C4F800396B6F03F1100243F4CB +:1024D00080136A67A362F8BD2438000840800010AA +:1024E000C26E90F86610D2F8003823F4FE6343EA17 +:1024F0000113C2F8003870472DE9F84300EB81035F +:10250000C56EDA68166806F00306731E022B05EB2B +:1025100041130C4680460FFA81F94FEA41104FF003 +:102520000001C3F8101B4FF0010104F1100398BF24 +:10253000B60401FA03F391698EBF334E06F180565B +:1025400006F5004600293AD0578A04F1580149019E +:1025500037436F50D5F81C180B43C5F81C382B189F +:102560000021C3F8101953690127611EA7409BB3CE +:10257000138A928B9B08012A88BF5343D8F8742092 +:10258000981842EA034301F1400205EB8202C8F8C1 +:102590007400214653602846FFF7CAFE08EB890005 +:1025A000C3681B8A43EA8453483464011E432E5196 +:1025B000D5F81C381F43C5F81C78BDE8F88305EB37 +:1025C0004917D7F8001B21F40041C7F8001BD5F8C4 +:1025D0001C1821EA0303C0E704F13F0305EB830362 +:1025E0000A4A5A6028462146FFF7A2FE05EB491029 +:1025F000D0F8003923F40043C0F80039D5F81C386E +:1026000023EA0707D7E700BF00800010000400029C +:10261000026F12684267FFF75FBE00005831C36E59 +:1026200049015B5813F4004004D013F4001F0CBFA1 +:1026300002200120704700004831C36E49015B58F9 +:1026400013F4004004D013F4001F0CBF022001203B +:102650007047000000EB8101CB68196A0B681360BA +:102660004B6853607047000000EB810330B5DD68B4 +:10267000AA691368D36019B9402B84BF4023136043 +:102680006B8A1468C26E1C44013CB4FBF3F46343D0 +:10269000033323F0030302EB411043EAC44343F046 +:1026A000C043C0F8103B2B6803F00303012B09B2B1 +:1026B0000ED1D2F8083802EB411013F4807FD0F825 +:1026C000003B14BF43F0805343F00053C0F8003B7D +:1026D00002EB4112D2F8003B43F00443C2F8003B46 +:1026E00030BD00002DE9F041254DEE6E06EB4013A4 +:1026F0000446D3F8087BC3F8087B38070AD5D6F818 +:102700001438190706D505EB84032146DB682846F3 +:102710005B689847FA0721D5D6F81438DB071DD532 +:1027200005EB8403D968DCB98B69488A5A68B2FB27 +:10273000F0F600FB16229AB91868DA6890420FD2B8 +:10274000121AC3E9002472B6302383F3118862B6EB +:102750000B482146FFF788FF84F31188BDE8F0811C +:10276000012303FA04F26B8923EA02036B81CB682D +:10277000002BF3D021460248BDE8F041184700BFC6 +:10278000782D012000EB810370B5DD68C36E6C69A4 +:102790002668E6604A0156BB1A444FF40020C2F88E +:1027A00010092A6802F00302012A0AB20ED1D3F8F6 +:1027B000080803EB421410F4807FD4F8000914BF1A +:1027C00040F0805040F00050C4F8000903EB421282 +:1027D000D2F8000940F00440C2F80009D3F83408E8 +:1027E000012202FA01F10143C3F8341870BD19B98E +:1027F000402E84BF4020206020682E8A8419013C2E +:10280000B4FBF6F440EAC44040F000501A44C6E776 +:102810002DE9F8433C4DEE6E06EB40130446D3F829 +:102820000889C3F8088918F0010F4FEA40171CD037 +:10283000D6F81038DB0718D505EB8003D9684B694B +:102840001868DA68904232D2121A4FF000091A6002 +:10285000C3F8049072B6302383F3118862B6214620 +:102860002846FFF78FFF89F3118818F0800F1CD0DE +:10287000D6F834380126A640334216D005EB84033F +:10288000ED6ED3F80CC0DCF814200134E4B2D2F8B9 +:1028900000E005EB04342F445168714515D3D5F899 +:1028A000343823EA0606C5F83468BDE8F883012306 +:1028B00003FA04F22B8923EA02032B818B68002B95 +:1028C000D3D0214628469847CFE7BCF81000AEEB9E +:1028D0000103834228BF0346D7F8180980B2B3EB3F +:1028E000800FE2D89068A0F1040959F8048FC4F869 +:1028F0000080A0EB09089844B8F1040FF5D81844FB +:102900000B4490605360C7E7782D01202DE9F74F05 +:10291000AC4CE56E6E69AB691E4016F480586E6172 +:1029200007D02046FEF7ECFC03B0BDE8F04F00F006 +:102930006BBC002E12DAD5F8003EA2489B071EBFE2 +:10294000D5F8003E23F00303C5F8003ED5F804385F +:1029500023F00103C5F80438FEF7FEFC370505D562 +:102960009848FFF7B9FC9748FEF7E4FCB0040CD593 +:10297000D5F8083813F0060FEB6823F470530CBF3A +:1029800043F4105343F4A053EB6031071BD5636845 +:10299000DB681BB9AB6923F00803AB612378052B17 +:1029A0000CD1D5F8003E87489A071EBFD5F8003EE7 +:1029B00023F00303C5F8003EFEF7CEFC6368DB6836 +:1029C0000BB180489847F30200F18980B70227D500 +:1029D000D4F86C90DFF8ECB100274FF0010A09EB56 +:1029E0004712D2F8003B03F44023B3F5802F11D1F6 +:1029F000D2F8003B002B0DDA62890AFA07F322EACB +:102A00000303638104EB8703DB68DB6813B139469A +:102A100058469847236F01379B68FFB29F42DED923 +:102A2000F00617D5E76E3A6AC2F30A1002F00F03F8 +:102A300002F4F012B2F5802F00F09980B2F5402F29 +:102A400008D104EB83030022DB681B6A07F580577B +:102A500090427ED13303D5F818481DD5E70302D53F +:102A60000020FFF73FFEA50302D50120FFF73AFE45 +:102A7000600302D50220FFF735FE210302D50320B3 +:102A8000FFF730FEE20202D50420FFF72BFEA3027F +:102A900002D50520FFF726FE77037FF545AFE60751 +:102AA00002D50020FFF7B4FEA50702D50120FFF7ED +:102AB000AFFE600702D50220FFF7AAFE210702D56C +:102AC0000320FFF7A5FEE20602D50420FFF7A0FED3 +:102AD000A3067FF529AF0520FFF79AFE24E7E36EF2 +:102AE000DFF8E0A0019300274FF00109236F9B68F6 +:102AF0005FFA87FB9B453FF669AF019B03EB4B13E6 +:102B0000D3F8001901F44021B1F5802F1FD1D3F87B +:102B1000001900291BDAD3F8001941F09041C3F8DD +:102B20000019D3F800190029FBDB5946E06EFFF7C6 +:102B3000FFFB218909FA0BF321EA0303238104EB4C +:102B40008B03DB689B6813B15946504698470137A1 +:102B5000CCE7910708BFD7F80080072A98BF03F891 +:102B6000018B02F1010298BF4FEA182870E7023387 +:102B700004EB830207F580575268D2F818C0DCF8DE +:102B80000820DCE9001CA1EB0C0C002188420AD1D2 +:102B900004EB830463689B699A6802449A605A68EC +:102BA00002445A6056E711F0030F08BFD7F80080BF +:102BB0008C4588BF02F8018B01F1010188BF4FEA03 +:102BC0001828E3E7782D0120C36E03EB4111D1F8FB +:102BD000003B43F40013C1F8003B7047C36E03EBA6 +:102BE0004111D1F8003943F40013C1F8003970479E +:102BF000C36E03EB4111D1F8003B23F40013C1F87D +:102C0000003B7047C36E03EB4111D1F8003923F448 +:102C10000013C1F80039704700F1604303F56143C8 +:102C20000901C9B283F80013012200F01F039A4082 +:102C300043099B0003F1604303F56143C3F880211E +:102C40001A60704772B6302383F3118862B67047FA +:102C500030B5039C0172043304FB0325C0E906531D +:102C6000049B03630021059BC160C0E90000C0E92B +:102C70000422C0E90842C0E90A11436330BD0000E4 +:102C8000416A0022C0E90411C0E90A22C2606FF063 +:102C90000101FEF76FBE0000D0E90432934201D17A +:102CA000C2680AB9181D704700207047036919608F +:102CB000C2680132C260C2691344826903619342EF +:102CC00024BF436A03610021FEF748BE38B50446BD +:102CD0000D46E3683BB16269131D1268A362134499 +:102CE000E362002007E0237A33B929462046FEF745 +:102CF00025FE0028EDDA38BD6FF00100FBE700008B +:102D0000C368C269013BC36043691344826943617C +:102D1000934224BF436A436100238362036B03B180 +:102D20001847704770B5FFF78DFF866A04463EB9B5 +:102D3000FFF7CCFF054618B186F31188284670BD11 +:102D4000A36AE26A13F8015BA362934202D32046AE +:102D5000FFF7D6FF002383F31188EFE72DE9F04753 +:102D60009846FFF76FFF002504460E461746A94612 +:102D7000D4F828A0BAF1000F09D141462046FFF748 +:102D8000A5FF20B18AF311882846BDE8F087D4E971 +:102D90000A12A7EB050A521A924528BF9246BAF1C9 +:102DA000400F1BD9334601F1400251F8040B43F8A0 +:102DB000040B9142F9D1A36A40334036A3624035F7 +:102DC000D4E90A239A4202D32046FFF799FF89F3F8 +:102DD0001188BD42D8D2FFF735FFC9E730465246C9 +:102DE000FDF7BAFFA36A53445644A3625544E7E78C +:102DF00010B5029C0172043303FB0421C0E90613E1 +:102E00000023C0E90A33039B0363049BC460C0E949 +:102E10000000C0E90422C0E90842436310BD00007D +:102E2000026AC260426AC0E904220022C0E90A22A2 +:102E30006FF00101FEF79EBDD0E904239A4201D153 +:102E4000C26822B9184650F8043B0B607047002353 +:102E50001846FAE7C368C2690133C3604369134483 +:102E600082694361934224BF436A43610021FEF7B4 +:102E700075BD000038B504460D46E3683BB12369D3 +:102E80001A1DA262E2691344E362002007E0237A7C +:102E900033B929462046FEF751FD0028EDDA38BD4A +:102EA0006FF00100FBE7000003691960C268013A96 +:102EB000C260C269134482690361934224BF436ABA +:102EC000036100238362036B03B11847704700005E +:102ED00070B5FFF7B7FE866A0D46044611462EB957 +:102EE000FFF7C8FF10B186F3118870BDA36A1D708B +:102EF000A36AE26A01339342A36204D3E1692046E4 +:102F00000439FFF7D1FF002080F31188EDE70000BE +:102F10002DE9F0479946FFF795FE002604460D4639 +:102F20009046B246A76A4FB949462046FFF7A2FF2E +:102F300020B187F311883046BDE8F087D4E90A074D +:102F40003A1AA8EB0607974228BF1746402F1BD90D +:102F500005F1400355F8042B40F8042B9D42F9D1AC +:102F6000A36A4033A3624036D4E90A239A4204D3C9 +:102F7000E16920460439FFF797FF8AF31188464537 +:102F8000D9D2FFF75FFECDE729463A46FDF7E4FECA +:102F9000A36A3B443D44A3623E44E5E7D0E90423F1 +:102FA0009A4217D1C3689BB1836A8BB1043B9B1AC9 +:102FB0000ED01360C368013BC360C3691A448369C0 +:102FC00002619A4224BF436A0361002383620123A2 +:102FD000184670470023FBE700F042B94FF08043EA +:102FE000586A70474FF08043002258631A610222EA +:102FF000DA6070474FF080430022DA6070470000CB +:103000004FF0804358637047FEE7000070B51B4BDC +:1030100001630025044686B0586085620E4600F0C4 +:10302000CBF804F11003C4E904334FF0FF33C4E9D3 +:103030000635C4E90044A560E562FFF7CFFF2B46E3 +:103040000246C4E9082304F134010D4A25658023B2 +:103050002046FEF727FC0123E0600A4A0375009230 +:1030600072680192B268CDE90223074B6846CDE948 +:103070000435FEF73FFC06B070BD00BF20260120DE +:10308000543800085938000809300008024AD36A49 +:103090001843D062704700BFB82301204B684360DB +:1030A0008B688360CB68C3600B6943614B690362C3 +:1030B0008B6943620B6803607047000008B52C4BB6 +:1030C0002C481A6940F2FF710A431A611A6922F406 +:1030D000FF6222F007021A611A691A6B0A431A6327 +:1030E0001A6D0A431A65244A1B6D1146FFF7D6FF75 +:1030F00002F11C0100F58060FFF7D0FF02F13801FA +:1031000000F58060FFF7CAFF02F1540100F580600E +:10311000FFF7C4FF02F1700100F58060FFF7BEFF0A +:1031200002F18C0100F58060FFF7B8FF02F1A80101 +:1031300000F58060FFF7B2FF02F1C40100F5806086 +:10314000FFF7ACFF02F1E00100F58060FFF7A6FF9A +:1031500002F1FC0100F58060FFF7A0FF02F58C7121 +:1031600000F58060FFF79AFFBDE8084000F0EEB878 +:1031700000380240000002406038000808B500F046 +:1031800059FAFEF767FBFFF705F8BDE80840FEF7C0 +:10319000E1BD000070470000EFF3098305494A6B69 +:1031A00022F001024A63683383F30988002383F322 +:1031B0001188704700EF00E0302080F3118862B67C +:1031C0000D4B0E4AD96821F4E0610904090C0A4349 +:1031D000DA60D3F8FC200A4942F08072C3F8FC2080 +:1031E000084AC2F8B01F116841F0010111602022A5 +:1031F000DA7783F82200704700ED00E00003FA055B +:1032000055CEACC5001000E010B572B6302383F384 +:10321000118862B60E4B5B6813F4006314D0F1EEB4 +:10322000103AEFF30984683C4FF08073E361094B77 +:10323000DB6B236684F30988FEF7ECFA10B1064BCA +:10324000A36110BD054BFBE783F31188F9E700BFCD +:1032500000ED00E000EF00E04F030008520300081B +:103260000F4B1A6C42F001021A641A6E42F001020E +:103270001A660C4A1B6E936843F0010393604FF08B +:1032800080436B229A624FF0FF32DA6200229A6129 +:103290005A63DA605A6001225A611A60704700BFAF +:1032A00000380240002004E04FF0804208B5116968 +:1032B000D3680B40D9B2C9439B07116109D572B6D7 +:1032C000302383F3118862B6FEF7DAFA002383F322 +:1032D000118808BD1B4B1A696FEA42526FEA5252BD +:1032E0001A611A69C2F30A021A614FF0FF301A69B3 +:1032F0005A69586100215A6959615A691A6A62F01B +:1033000080521A621A6A02F080521A621A6A5A6A63 +:1033100058625A6A59625A6A0B4A106840F48070BF +:103320001060186F00F44070B0F5007F1EBF4FF4BE +:10333000803018671967536823F40073536000F0F6 +:1033400055B900BF0038024000700040374B4FF0C5 +:1033500080521A64364A4FF4404111601A6842F0B4 +:1033600001021A601A689207FCD59A6822F00302DB +:103370009A602E4B9A6812F00C02FBD1196801F08A +:10338000F90119609A601A6842F480321A601A686A +:103390009003FCD55A6F42F001025A67234B5A6FD3 +:1033A0009107FCD5234A5A601A6842F080721A606D +:1033B0001F4B5A685204FCD51A6842F480321A60D6 +:1033C0005A68D003FCD51A6842F400321A60184AD1 +:1033D00053689903FCD5154B1A689201FCD5164A1F +:1033E0009A6040F20112C3F88C200022C3F89020AA +:1033F000124A40F207331360136803F00F03072BE0 +:10340000FAD10A4B9A6842F002029A609A6802F076 +:103410000C02082AFAD15A6C42F480425A645A6E5D +:1034200042F480425A665B6E704700BF003802402B +:1034300000700040086C400900948838003C02404D +:10344000074A08B5536903F00103536123B1054AE4 +:1034500013680BB150689847BDE80840FFF7D4BE29 +:10346000003C0140082E0120074A08B5536903F0CB +:103470000203536123B1054A93680BB1D0689847A2 +:10348000BDE80840FFF7C0BE003C0140082E012007 +:10349000074A08B5536903F00403536123B1054A91 +:1034A00013690BB150699847BDE80840FFF7ACBEFF +:1034B000003C0140082E0120074A08B5536903F07B +:1034C0000803536123B1054A93690BB1D06998474A +:1034D000BDE80840FFF798BE003C0140082E0120DF +:1034E000074A08B5536903F01003536123B1054A35 +:1034F000136A0BB1506A9847BDE80840FFF784BED5 +:10350000003C0140082E0120164B10B55C6904F404 +:1035100078725A61A30604D5134A936A0BB1D06A34 +:103520009847600604D5104A136B0BB1506B98474F +:10353000210604D50C4A936B0BB1D06B9847E2057A +:1035400004D5094A136C0BB1506C9847A30504D5F8 +:10355000054A936C0BB1D06C9847BDE81040FFF75B +:1035600053BE00BF003C0140082E0120194B10B58E +:103570005C6904F47C425A61620504D5164A136DF5 +:103580000BB1506D9847230504D5134A936D0BB1C9 +:10359000D06D9847E00404D50F4A136E0BB1506EFE +:1035A0009847A10404D50C4A936E0BB1D06E98478E +:1035B000620404D5084A136F0BB1506F9847230477 +:1035C00004D5054A936F0BB1D06F9847BDE8104002 +:1035D000FFF71ABE003C0140082E012008B5FFF796 +:1035E00063FEBDE80840FFF70FBE0000062108B5E6 +:1035F0000846FFF711FB06210720FFF70DFB062108 +:103600000820FFF709FB06210920FFF705FB06212B +:103610000A20FFF701FB06211720FFF7FDFA06211C +:103620002820FFF7F9FABDE8084007211C20FFF722 +:10363000F3BA000008B5FFF74DFE00F00BF8FDF7F8 +:10364000F1FDFDF7C3FCFFF7A5FDBDE80840FFF75E +:10365000C3BC00000023054A19460133102BC2E900 +:10366000001102F10802F8D1704700BF082E0120B6 +:10367000034611F8012B03F8012B002AF9D17047FA +:1036800053544D3332463F3F3F3F3F3F0053544D2D +:10369000333246375B347C355D780053544D3332DA +:1036A00046375B367C375D78000000000000000084 +:1036B000490F0008350F0008710F00085D0F000862 +:1036C000690F0008550F0008410F00082D0F000872 +:1036D0007D0F000800000000010000000000000055 +:1036E00063300000E036000810240120202601206D +:1036F0004172647550696C6F740025424F415244A9 +:10370000252D424C002553455249414C25000000CF +:10371000020000000000000065110008D11100083F +:1037200040004000C02A0120D02A012002000000F1 +:103730000000000003000000000000001512000857 +:103740000000000010000000E02A0120000000003E +:103750000100000000000000782D0120010102009E +:10376000F51C0008091C0008A11C0008891C0008A1 +:10377000430000007837000809024300020100C03E +:1037800032090400000102020100052400100105B5 +:103790002401000104240202052406000107058219 +:1037A000030800FF09040100020A000000070501E8 +:1037B00002400000070581024000000012000000E6 +:1037C000C4370008120110010200004009124157DD +:1037D00000020102030100000403090425424F41D5 +:1037E00052442500426C69747A463734354D696E0F +:1037F0006900303132333435363738394142434449 +:1038000045460000008000000080000000800000AD +:10381000008000000000020000000400000004001E +:1038200000000400000000007113000821160008C9 +:10383000C916000840004000F02D0120F02D0120A5 +:1038400001000000002E0120800000004001000067 +:10385000050000006D61696E0069646C6500000020 +:103860000001806A00000000AAAAAAAA0001006460 +:10387000FFFF00000000000000A00A0000000000A0 +:1038800000000000AAAAAAAA00000000FFFF000092 +:103890000000000000000000000004000000000024 +:1038A000AAAAAAAA00000000FFFD00000000000074 +:1038B000000000000000000000000000AAAAAAAA60 +:1038C00000000000FFFF00000000000000000000FA +:1038D0000001000000000000AAAAAAAA000100003E +:1038E000FFFF0000000000000000000000000000DA +:1038F00000000000AAAAAAAA00000000FFFF000022 +:1039000000000000000000000000000000000000B7 +:10391000AAAAAAAA00000000FFFF00000000000001 +:103920000000000000000000000000000A0000008D +:103930000000000003000000000000000000000084 +:103940000000000000000000000000000000000077 +:103950000000000000000000000000000000000067 +:103960000000000000000000000000000000000057 +:103970000000000000000000000000000000000047 +:103980000000000000000000000000000000000037 +:1039900000000000000000008B0400000000000098 +:1039A00000800E0000000000FF000000000000008A +:1039B00080360008490400008D36000851040000DC +:1039C0009B360008009600000000080096000000EA +:1039D0000008000004000000D837000800000000C4 +:1039E00000000000000000000000000000000000D7 +:0439F00000000000D3 +:00000001FF diff --git a/Tools/bootloaders/BlitzWingH743_bl.bin b/Tools/bootloaders/BlitzWingH743_bl.bin new file mode 100644 index 0000000000000..08a22a32f9658 Binary files /dev/null and b/Tools/bootloaders/BlitzWingH743_bl.bin differ diff --git a/Tools/bootloaders/BlitzWingH743_bl.hex b/Tools/bootloaders/BlitzWingH743_bl.hex new file mode 100644 index 0000000000000..275e235c6dda6 --- /dev/null +++ b/Tools/bootloaders/BlitzWingH743_bl.hex @@ -0,0 +1,1103 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200086928000870 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008D53D0008013E000865 +:100060002D3E0008593E0008853E0008711000082A +:1000700099100008C5100008F11000081D110008B3 +:100080004511000871110008E3020008E3020008AE +:10009000E3020008E3020008E3020008B13E0008A2 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000153F0008E3020008E3020008E3020008ED +:1000F000E3020008E3020008E30200089D11000883 +:10010000E3020008E3020008893F0008E302000858 +:10011000E3020008E3020008E3020008E30200082B +:10012000C9110008F11100081D1200084912000849 +:1001300075120008E3020008E3020008E302000869 +:10014000E3020008E3020008E3020008E3020008FB +:100150009D120008C9120008F5120008E302000809 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000855340008E3020008E302000827 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000841340008E3020008E3020008DB +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0EEFA86 +:1003500003F0FCFA4FF055301F491B4A91423CBF55 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F006FB03F05AFBFE +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0EEBA00060020002200207C +:1003D0000000000808ED00E00000002000060020FA +:1003E00068440008002200205C22002060220020D7 +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0A4FDFEE701F056 +:1004300033FD00DFFEE7000038B500F02FFC00F0D0 +:10044000ABFD02F0D1F9054602F004FA0446C0B94A +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0C8F90CB100F078 +:1004700075F800F065FD284600F01EF900F06EF8F2 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F021FE0023154A4FF4D1 +:1004D0007A71134801F010FE002383F31188124C47 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F088FC322363602B78032B07D16368EB +:100510002BB9022000F07EFC4FF47A73636038BD83 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F05DBC022000F050BC024B0022F3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F5C0239A4280F088800020C5 +:1005900000F09EFB0220FFF7CBFF454B0021D3F874 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000060820000608FFFF050800220020C1 +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0E3FBB14AB8 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F011FD0023AB4A4FF4F0 +:1006F0007A71A94801F000FD002383F31188009B63 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F06BFB24B19C4B1B6860 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F051FB039B213B1F2B10 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F03FFA0421059005A800F00EFA04 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F058FB26B10BF03D +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F00EFA0220FFF73BFE1FFA86F84046D2 +:1008C00000F016FA0446B0B1039940460136A1F192 +:1008D00040025142514100F01BFA0028EDD1BA46C6 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0E4F9013040F07B +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F032FA019AFF217F4800F053FA4FEAF3 +:1009F000A803C8F387027C492846019300F052FA05 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F096F918 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0F7FA8046E7E7384600F03AF945 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F051F90590E6E70023642104A8CA +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F03FF9EAE717 +:100AC0000220FFF7E5FC00283FF48CAE00F04EF961 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F049F907460421049004A800F0FE +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0CEF80421059005A800F0A1 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F0FBF8002844D00A9B01330BD0CB +:100B600008220AA9002000F09DF900283AD020228E +:100B7000FF210AA800F08EF9FFF792FC1C4801F053 +:100B8000FFF913B0BDE8F08F002E3FF42BAE0BF051 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0DDF9059800F0E4F946463C462E +:100BD00000F0ACF9A6E506464EE64FF0000901E646 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0A8F98B +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B50A4E54 +:100CA00000240A4D01F088FC308028683388834294 +:100CB00008D901F07DFC2B6804440133B4F5C02F42 +:100CC0002B60F2D370BD00BFB62300208823002024 +:100CD00001F040BD00F1006000F5C02000687047E1 +:100CE00000F10060920000F5C02001F0C1BC0000DE +:100CF000054B1A68054B1B889B1A834202D9104486 +:100D000001F056BC0020704788230020B623002045 +:100D100038B50446074D29B128682044BDE838405D +:100D200001F05EBC2868204401F048FC0028F3D0A4 +:100D300038BD00BF882300200020704700F1FF501D +:100D400000F58F10D0F8000870470000064991F8B0 +:100D5000243033B100230822086A81F82430FFF7D9 +:100D6000BFBF0120704700BF8C230020014B1868D3 +:100D7000704700BF0010005C194B01380322084483 +:100D800070B51D68174BC5F30B042D0C1E88A642C9 +:100D90000BD15C680A46013C824213460FD214F91B +:100DA000016F4EB102F8016BF6E7013A03F1080357 +:100DB000ECD181420B4602D22C2203F8012B0424F1 +:100DC000094A1688AE4204D1984284BF967803F847 +:100DD000016B013C02F10402F3D1581A70BD00BF4F +:100DE0000010005C1422002080400008022803D17B +:100DF000024B4FF080729A61704700BF00000258AA +:100E0000022803D1024B4FF480729A61704700BFF1 +:100E100000000258022804D1024A536983F4807307 +:100E2000536170470000025870B504464FF47A765B +:100E30004CB1412C254628BF412506FB05F0641B1B +:100E400001F09EF8F4E770BD002310B5934203D083 +:100E5000CC5CC4540133F9E710BD0000013810B573 +:100E600010F9013F3BB191F900409C4203D11AB106 +:100E70000131013AF4E71AB191F90020981A10BD36 +:100E80001046FCE703460246D01A12F9011B00295E +:100E9000FAD1704702440346934202D003F8011B83 +:100EA000FAE770472DE9F8431F4D14460746884678 +:100EB00095F8242052BBDFF870909CB395F824304D +:100EC0002BB92022FF2148462F62FFF7E3FF95F858 +:100ED00024004146C0F1080205EB8000A24228BF71 +:100EE0002246D6B29200FFF7AFFF95F82430A41B3C +:100EF00017441E449044E4B2F6B2082E85F82460EC +:100F0000DBD1FFF723FF0028D7D108E02B6A03EBE2 +:100F100082038342CFD0FFF719FF0028CBD10020F6 +:100F2000BDE8F8830120FBE78C230020024B1A78F0 +:100F3000024B1A70704700BFB4230020102200201B +:100F400010B5114C114800F06FFB21460F4800F01E +:100F500097FB24684FF47A70D4F89020D2F80438C4 +:100F600043F00203C2F80438FFF75EFF0849204649 +:100F700000F094FCD4F89020D2F8043823F0020357 +:100F8000C2F8043810BD00BF3C420008B026002063 +:100F90004442000870470000F0B5A1B071B60023CC +:100FA0000120002480261A46194600F04BFA4FF41F +:100FB000D067214A3D25136923BBD2F810310BBB02 +:100FC000036804F1006199600368C3F80CD00368FA +:100FD0005E6003681F6001680B6843F001030B60EB +:100FE00001680B6823F01E030B6001680B68DB07C8 +:100FF000FCD4037B8034416805FA03F3B4F5001F89 +:101000000B60D8D100F05EFAB4F5001F11D00024B7 +:101010000A4E0B4D012001F09DFB3388A34205D9F8 +:1010200028682044013401F0DBFAF6E7002001F0E3 +:1010300091FB61B621B0F0BD00200052B623002024 +:101040008823002030B50A44084D91420DD011F894 +:10105000013B5840082340F30004013B2C4013F0AF +:10106000FF0384EA5000F6D1EFE730BD2083B8EDEE +:1010700008B5074B074A196801F03D0199605368AC +:101080000BB190689847BDE8084001F025BC00BF4F +:1010900000000240B823002008B5084B19688909F0 +:1010A00001F03D018A019A60054AD3680BB11069CD +:1010B0009847BDE8084001F00FBC00BF00000240A7 +:1010C000B823002008B5084B1968090C01F03D0150 +:1010D0000A049A60054A53690BB190699847BDE8C4 +:1010E000084001F0F9BB00BF00000240B823002017 +:1010F00008B5084B1968890D01F03D018A059A6011 +:10110000054AD3690BB1106A9847BDE8084001F061 +:10111000E3BB00BF00000240B823002008B5074B26 +:10112000074A596801F03D01D960536A0BB1906AD2 +:101130009847BDE8084001F0CFBB00BF0000024067 +:10114000B823002008B5084B5968890901F03D0112 +:101150008A01DA60054AD36A0BB1106B9847BDE883 +:10116000084001F0B9BB00BF00000240B8230020D6 +:1011700008B5084B5968090C01F03D010A04DA6012 +:10118000054A536B0BB1906B9847BDE8084001F0DE +:10119000A3BB00BF00000240B823002008B5084BE5 +:1011A0005968890D01F03D018A05DA60054AD36B63 +:1011B0000BB1106C9847BDE8084001F08DBB00BF33 +:1011C00000000240B823002008B5074B074A196801 +:1011D00001F03D019960536C0BB1906C9847BDE8EC +:1011E000084001F079BB00BF00040240B823002092 +:1011F00008B5084B1968890901F03D018A019A6018 +:10120000054AD36C0BB1106D9847BDE8084001F05A +:1012100063BB00BF00040240B823002008B5084BA0 +:101220001968090C01F03D010A049A60054A536DE2 +:101230000BB1906D9847BDE8084001F04DBB00BF71 +:1012400000040240B823002008B5084B1968890D36 +:1012500001F03D018A059A60054AD36D0BB1106E0D +:101260009847BDE8084001F037BB00BF00040240CA +:10127000B823002008B5074B074A596801F03D0123 +:10128000D960536E0BB1906E9847BDE8084001F0ED +:1012900023BB00BF00040240B823002008B5084B60 +:1012A0005968890901F03D018A01DA60054AD36E67 +:1012B0000BB1106F9847BDE8084001F00DBB00BFAF +:1012C00000040240B823002008B5084B5968090CF7 +:1012D00001F03D010A04DA60054A536F0BB1906FCB +:1012E0009847BDE8084001F0F7BA00BF000402408B +:1012F000B823002008B5084B5968890D01F03D015D +:101300008A05DA60054AD36F13B1D2F88000984796 +:10131000BDE8084001F0E0BA00040240B823002014 +:1013200000230C4910B51A460B4C0B6054F82300EF +:10133000026001EB430004334260402BF6D1074AC0 +:101340004FF0FF339360D360C2F80834C2F80C3416 +:1013500010BD00BFB82300209040000800000240EC +:101360000F28F8B510D9102810D0112811D0122844 +:1013700008D10F240720DFF8C8E00126DEF800506E +:10138000A04208D9002653E00446F4E70F240020C9 +:10139000F1E70724FBE706FA00F73D424AD1264C65 +:1013A0004FEA001C3D4304EB00160EEBC000CEF8E4 +:1013B0000050C0E90123FBB273B12048D0F8D83007 +:1013C00043F00103C0F8D830D0F8003143F00103F6 +:1013D000C0F80031D0F8003117F47F4F0ED0174815 +:1013E000D0F8D83043F00203C0F8D830D0F800313C +:1013F00043F00203C0F80031D0F8003154F80C007B +:10140000036823F01F030360056815F00105FBD195 +:1014100004EB0C033D2493F80CC05F6804FA0CF451 +:101420003C6021240560446112B1987B00F054F8BF +:101430003046F8BD0130A3E7904000080044025850 +:10144000B823002010B5302484F31188FFF788FFFB +:10145000002383F3118810BD10B50446807B00F093 +:1014600051F801231549627B03FA02F20B6823EA63 +:101470000203DAB20B6072B9114AD2F8D81021F027 +:101480000101C2F8D810D2F8001121F00101C2F810 +:101490000011D2F8002113F47F4F0ED1084BD3F87E +:1014A000D82022F00202C3F8D820D3F8002122F07D +:1014B0000202C3F80021D3F8003110BDB823002088 +:1014C0000044025808B5302383F31188FFF7C4FFA6 +:1014D000002383F3118808BD090100F16043012254 +:1014E00003F56143C9B283F8001300F01F039A406B +:1014F00043099B0003F1604303F56143C3F8802176 +:101500001A60704700F01F0301229A40430900F15E +:1015100060409B0000F5614003F1604303F56143C7 +:10152000C3F88020C3F88021002380F8003370477F +:10153000026843681143016003B118477047000017 +:1015400013B5406B00F58054D4F8A4381A681178AC +:10155000042914D1017C022911D11979012312899E +:101560008B4013420BD101A94C3002F0A5F8D4F8FE +:10157000A4480246019B2179206800F0DFF902B0FF +:1015800010BD0000143002F027B800004FF0FF3308 +:10159000143002F021B800004C3002F0F9B800001D +:1015A0004FF0FF334C3002F0F3B80000143001F07C +:1015B000F5BF00004FF0FF31143001F0EFBF000025 +:1015C0004C3002F0C5B800004FF0FF324C3002F052 +:1015D000BFB800000020704710B500F58054D4F863 +:1015E000A4381A681178042917D1017C022914D172 +:1015F0005979012352898B4013420ED1143001F0E6 +:1016000087FF024648B1D4F8A4484FF4407361798B +:101610002068BDE8104000F07FB910BD406BFFF7B7 +:10162000DBBF0000704700007FB5124B0125042688 +:10163000044603600023057400F1840243602946D8 +:10164000C0E902330C4B0290143001934FF4407305 +:10165000009601F039FF094B04F69442294604F143 +:101660004C000294CDE900634FF4407302F000F89F +:1016700004B070BD904100081D1600084115000817 +:101680000A68302383F311880B790B3342F8230067 +:101690004B79133342F823008B7913B10B3342F8A3 +:1016A000230000F58053C3F8A4180223037400201C +:1016B00080F311887047000038B5037F044613B1EA +:1016C00090F85430ABB90125201D0221FFF730FFFF +:1016D00004F114006FF00101257700F079FC04F1AA +:1016E0004C0084F854506FF00101BDE8384000F020 +:1016F0006FBC38BD10B5012104460430FFF718FF58 +:101700000023237784F8543010BD000038B5044618 +:101710000025143001F0F0FE04F14C00257701F0B3 +:10172000BFFF201D84F854500121FFF701FF204620 +:10173000BDE83840FFF750BF90F8803003F06003F9 +:10174000202B06D190F881200023212A03D81F2ABC +:1017500006D800207047222AFBD1C0E91D3303E0E0 +:10176000034A426707228267C3670120704700BFB0 +:101770002C22002037B500F58055D5F8A4381A681A +:10178000117804291AD1017C022917D11979012372 +:1017900012898B40134211D100F14C04204602F013 +:1017A0003FF858B101A9204601F086FFD5F8A448BA +:1017B0000246019B2179206800F0C0F803B030BDDB +:1017C00001F10B03F0B550F8236085B004460D46D7 +:1017D000FEB1302383F3118804EB8507301D082107 +:1017E000FFF7A6FEFB6806F14C005B691B681BB1A6 +:1017F000019001F06FFF019803A901F05DFF02461F +:1018000048B1039B2946204600F098F8002383F353 +:10181000118805B0F0BDFB685A691268002AF5D03E +:101820001B8A013B1340F1D104F18002EAE700007A +:10183000133138B550F82140ECB1302383F31188CF +:1018400004F58053D3F8A4281368527903EB82037C +:10185000DB689B695D6845B104216018FFF768FE8D +:10186000294604F1140001F05DFE2046FFF7B4FEA6 +:10187000002383F3118838BD7047000001F02AB9B6 +:1018800001234022002110B5044600F8303BFFF749 +:1018900001FB0023C4E9013310BD000010B5302363 +:1018A000044683F311882422416000210C30FFF7A5 +:1018B000F1FA204601F030F902230020237080F372 +:1018C000118810BD70B500EB8103054650690E46C6 +:1018D0001446DA6018B110220021FFF7DBFAA06984 +:1018E00018B110220021FFF7D5FA31462846BDE88D +:1018F000704001F017BA000083682022002103F035 +:10190000011310B5044683601030FFF7C3FA204678 +:10191000BDE8104001F092BAF0B4012500EB81045B +:1019200047898D40E4683D43A469458123600023D5 +:10193000A2606360F0BC01F0AFBA0000F0B4012512 +:1019400000EB810407898D40E4683D4364690581AB +:1019500023600023A2606360F0BC01F025BB00009F +:1019600070B5022300250446242203702946C0F8DE +:1019700088500C3040F8045CFFF78CFA204684F85D +:10198000705001F063F963681B6823B12946204653 +:10199000BDE87040184770BD0378052B10B50446AC +:1019A0000AD080F88C300523037043681B680BB1A4 +:1019B000042198470023A36010BD00000178052989 +:1019C00006D190F88C20436802701B6803B1184759 +:1019D0007047000070B590F87030044613B10023D2 +:1019E00080F8703004F18002204601F04BFA636801 +:1019F0009B68B3B994F8803013F0600535D00021AE +:101A0000204601F03DFD0021204601F02DFD6368D8 +:101A10001B6813B1062120469847062384F87030CE +:101A200070BD204698470028E4D0B4F88630A26FF5 +:101A30009A4288BFA36794F98030A56F002B4FF0BE +:101A4000300380F20381002D00F0F280092284F837 +:101A5000702083F3118800212046D4E91D23FFF76D +:101A60006DFF002383F31188DAE794F8812003F0F7 +:101A70007F0343EA022340F20232934200F0C58022 +:101A800021D8B3F5807F48D00DD8012B3FD0022B51 +:101A900000F09380002BB2D104F188026267022229 +:101AA000A267E367C1E7B3F5817F00F09B80B3F5E0 +:101AB000407FA4D194F88230012BA0D1B4F88830B3 +:101AC00043F0020332E0B3F5006F4DD017D8B3F501 +:101AD000A06F31D0A3F5C063012B90D86368204676 +:101AE00094F882205E6894F88310B4F88430B0478C +:101AF000002884D0436863670368A3671AE0B3F5DE +:101B0000106F36D040F6024293427FF478AF5C4BC0 +:101B100063670223A3670023C3E794F88230012B95 +:101B20007FF46DAFB4F8883023F00203A4F8883056 +:101B3000C4E91D55E56778E7B4F88030B3F5A06FC8 +:101B40000ED194F88230204684F88A3001F0DCF817 +:101B500063681B6813B10121204698470323237053 +:101B60000023C4E91D339CE704F18B036367012361 +:101B7000C3E72378042B10D1302383F31188204648 +:101B8000FFF7BAFE85F311880321636884F88B5050 +:101B900021701B680BB12046984794F88230002BC7 +:101BA000DED084F88B300423237063681B68002B1D +:101BB000D6D0022120469847D2E794F884302046B8 +:101BC0001D0603F00F010AD501F04EF9012804D0DB +:101BD00002287FF414AF2B4B9AE72B4B98E701F0C8 +:101BE00035F9F3E794F88230002B7FF408AF94F8CE +:101BF000843013F00F01B3D01A06204602D501F04D +:101C000057FCADE701F048FCAAE794F88230002BBE +:101C10007FF4F5AE94F8843013F00F01A0D01B06CA +:101C2000204602D501F02CFC9AE701F01DFC97E755 +:101C3000142284F8702083F311882B462A46294603 +:101C40002046FFF769FE85F31188E9E65DB11522AC +:101C500084F8702083F3118800212046D4E91D23E5 +:101C6000FFF75AFEFDE60B2284F8702083F31188FB +:101C70002B462A4629462046FFF760FEE3E700BFD1 +:101C8000C0410008B8410008BC41000838B590F8D0 +:101C900070300446002B3ED0063BDAB20F2A34D80F +:101CA0000F2B32D8DFE803F03731310822323131DF +:101CB0003131313131313737856FB0F886309D425F +:101CC00014D2C3681B8AB5FBF3F203FB12556DB93E +:101CD000302383F311882B462A462946FFF72EFE30 +:101CE00085F311880A2384F870300EE0142384F8F9 +:101CF0007030302383F31188002320461A4619469A +:101D0000FFF70AFE002383F3118838BDC36F03B1C8 +:101D100098470023E7E70021204601F0B1FB0021AE +:101D2000204601F0A1FB63681B6813B10621204621 +:101D300098470623D7E7000010B590F870300446A6 +:101D4000142B29D017D8062B05D001D81BB110BDF4 +:101D5000093B022BFBD80021204601F091FB00211A +:101D6000204601F081FB63681B6813B10621204601 +:101D70009847062319E0152BE9D10B2380F8703022 +:101D8000302383F3118800231A461946FFF7D6FD46 +:101D9000002383F31188DAE7C3689B695B68002B33 +:101DA000D5D1C36F03B19847002384F87030CEE7D4 +:101DB00000238268037503691B6899689142FBD20E +:101DC0005A68036042601060586070470023826860 +:101DD000037503691B6899689142FBD85A680360D0 +:101DE000426010605860704708B50846302383F39E +:101DF00011880B7D032B05D0042B0DD02BB983F359 +:101E0000118808BD8B6900221A604FF0FF3383618F +:101E1000FFF7CEFF0023F2E7D1E9003213605A60EA +:101E2000F3E70000FFF7C4BF054BD96808751868D1 +:101E3000026853601A600122D8600275FEF7E2BAA8 +:101E4000402400200C4B30B5DD684B1C87B00446A5 +:101E50000FD02B46094A684600F04EF92046FFF79E +:101E6000E3FF009B13B1684600F050F9A86907B082 +:101E700030BDFFF7D9FFF9E740240020E91D000835 +:101E8000044B1A68DB6890689B68984294BF0020F6 +:101E90000120704740240020084B10B51C68D8680A +:101EA000226853601A600122DC602275FFF78EFF02 +:101EB00001462046BDE81040FEF7A4BA40240020A9 +:101EC00038B5074C01230025064907482370656093 +:101ED00001F0E4FC0223237085F3118838BD00BFB4 +:101EE000A8260020C84100084024002000F044B982 +:101EF000034A516853685B1A9842FBD8704700BF89 +:101F0000001000E08B600223086108468B82704756 +:101F10008368A3F1840243F8142C026943F8442C2B +:101F2000426943F8402C094A43F8242CC268A3F1C3 +:101F3000200043F8182C022203F80C2C002203F88E +:101F40000B2C034A43F8102C704700BF1D040008F7 +:101F50004024002008B5FFF7DBFFBDE80840FFF78D +:101F600061BF0000024BDB6898610F20FFF75CBF88 +:101F700040240020302383F31188FFF7F3BF0000D3 +:101F800008B50146302383F311880820FFF75AFF74 +:101F9000002383F3118808BD064BDB6839B1426822 +:101FA00018605A60136043600420FFF74BBF4FF086 +:101FB000FF307047402400200368984206D01A681A +:101FC0000260506018469961FFF72CBF704700000F +:101FD00038B504460D462068844200D138BD0368F8 +:101FE00023605C608561FFF71DFFF4E7036810B5AF +:101FF0009C68A2420CD85C688A600B604C602160CF +:10200000596099688A1A9A604FF0FF33836010BD57 +:10201000121B1B68ECE700000A2938BF0A2170B5C3 +:1020200004460D460A26601901F030FC01F018FC48 +:10203000041BA54203D8751C04462E46F3E70A2E5E +:1020400004D90120BDE8704001F068BC70BD0000FB +:10205000F8B5144B0D460A2A4FF00A07D96103F16F +:102060001001826038BF0A2241601969144601607C +:1020700048601861A81801F0F9FB01F0F1FB431B5F +:102080000646A34206D37C1C28192746354601F094 +:10209000FDFBF2E70A2F04D90120BDE8F84001F06A +:1020A0003DBCF8BD40240020F8B506460D4601F0C1 +:1020B000D7FB0F4A134653F8107F9F4206D12A469A +:1020C00001463046BDE8F840FFF7C2BFD169BB68A2 +:1020D000441A2C1928BF2C46A34202D92946FFF7DF +:1020E0009BFF224631460348BDE8F840FFF77EBF1C +:1020F0004024002050240020C0E90323002310B412 +:102100005DF8044B4361FFF7CFBF000010B5194CD9 +:10211000236998420DD08168D0E9003213605A607B +:102120009A680A449A60002303604FF0FF33A3616A +:1021300010BD0268234643F8102F5360002202604E +:1021400022699A4203D1BDE8104001F099BB93681F +:1021500081680B44936001F083FB2269E169926816 +:10216000441AA242E4D91144BDE81040091AFFF70D +:1021700053BF00BF402400202DE9F047DFF8BC80AA +:1021800008F110072C4ED8F8105001F069FBD8F870 +:102190001C40AA68031B9A423ED814444FF0000921 +:1021A000D5E90032C8F81C4013605A60C5F80090A9 +:1021B000D8F81030B34201D101F062FB89F31188E5 +:1021C000D5E9033128469847302383F311886B699A +:1021D000002BD8D001F044FB6A69A0EB04098246C9 +:1021E0004A450DD2022001F099FB0022D8F81030A8 +:1021F000B34208D151462846BDE8F047FFF728BF53 +:10220000121A2244F2E712EB09092946384638BF70 +:102210004A46FFF7EBFEB5E7D8F81030B34208D0D6 +:102220001444C8F81C00211AA960BDE8F047FFF764 +:10223000F3BEBDE8F08700BF5024002040240020FA +:1022400000207047FEE70000704700004FF0FF30AD +:102250007047000002290CD0032904D00129074847 +:1022600018BF00207047032A05D8054800EBC200BC +:102270007047044870470020704700BFA042000824 +:102280003C2200205442000870B59AB0054608462A +:10229000144601A900F0C2F801A8FEF7F3FD431CA3 +:1022A0000022C6B25B001046C5E900342370032348 +:1022B000023404F8013C01ABD1B202348E4201D8A1 +:1022C0001AB070BD13F8011B013204F8010C04F8B8 +:1022D000021CF1E708B5302383F311880348FFF7A8 +:1022E00049FA002383F3118808BD00BFB0260020FF +:1022F00090F8803003F01F02012A07D190F8812066 +:102300000B2A03D10023C0E91D3315E003F060035D +:10231000202B08D1B0F884302BB990F88120212AE5 +:1023200003D81F2A04D8FFF707BA222AEBD0FAE70E +:10233000034A426707228267C3670120704700BFD4 +:102340003322002007B5052917D8DFE801F0191658 +:1023500003191920302383F31188104A01210190B9 +:10236000FFF7B0FA019802210D4AFFF7ABFA0D48CA +:10237000FFF7CCF9002383F3118803B05DF804FB69 +:10238000302383F311880748FFF796F9F2E73023EB +:1023900083F311880348FFF7ADF9EBE7F441000838 +:1023A00018420008B026002038B50C4D0C4C2A46C7 +:1023B0000C4904F10800FFF767FF05F1CA0204F1B8 +:1023C00010000949FFF760FF05F5CA7204F1180013 +:1023D0000649BDE83840FFF757BF00BF883F0020DF +:1023E0003C220020D4410008DE410008E9410008F9 +:1023F00070B5044608460D46FEF744FDC6B22046B9 +:10240000013403780BB9184670BD32462946FEF7F1 +:1024100025FD0028F3D10120F6E700002DE9F04763 +:1024200005460C46FEF72EFD2B49C6B22846FFF79F +:10243000DFFF08B10636F6B228492846FFF7D8FF75 +:1024400008B11036F6B2632E0BD8DFF88C80DFF8B7 +:102450008C90234FDFF894A02E7846B92670BDE803 +:10246000F08729462046BDE8F04701F0EBBD252E58 +:102470002ED1072241462846FEF7F0FC70B9194BD1 +:10248000224603F10C0153F8040B8B4242F8040B73 +:10249000F9D11B7807350D341370DDE70822494662 +:1024A0002846FEF7DBFC98B9A21C0F4B19780232C4 +:1024B0000909C95D02F8041C13F8011B01F00F01A2 +:1024C0005345C95D02F8031CF0D118340835C3E741 +:1024D000013504F8016BBFE7C0420008E94100087C +:1024E000D6420008C842000800E8F11F0CE8F11FBE +:1024F000BFF34F8F044B1A695107FCD1D3F8102159 +:102500005207F8D1704700BF0020005208B50D4BAC +:102510001B78ABB9FFF7ECFF0B4BDA68D10704D59A +:102520000A4A5A6002F188325A60D3F80C21D20765 +:1025300006D5064AC3F8042102F18832C3F8042103 +:1025400008BD00BFE641002000200052230167457E +:1025500008B5114B1B78F3B9104B1A69510703D515 +:10256000DA6842F04002DA60D3F81021520705D54C +:10257000D3F80C2142F04002C3F80C21FFF7B8FF5A +:10258000064BDA6842F00102DA60D3F80C2142F01F +:102590000102C3F80C2108BDE641002000200052D2 +:1025A0000F289ABF00F580604004002070470000AB +:1025B0004FF4003070470000102070470F2808B516 +:1025C0000BD8FFF7EDFF00F500330268013204D1AC +:1025D00004308342F9D1012008BD0020FCE700004F +:1025E0000F2838B505463FD8FFF782FF1F4CFFF78D +:1025F0008DFF4FF0FF3307286361C4F814311DD8F5 +:102600002361FFF775FF030243F02403E360E368EF +:1026100043F08003E36023695A07FCD42846FFF7A0 +:1026200067FFFFF7BDFF4FF4003100F0F5F82846D3 +:10263000FFF78EFFBDE83840FFF7C0BFC4F8103188 +:10264000FFF756FFA0F108031B0243F02403C4F870 +:102650000C31D4F80C3143F08003C4F80C31D4F8B9 +:1026600010315B07FBD4D9E7002038BD00200052B1 +:102670002DE9F84F05460C46104645EA0203DE06F2 +:1026800002D00020BDE8F88F20F01F00DFF8BCB0BA +:10269000DFF8BCA0FFF73AFF04EB0008444503D184 +:1026A0000120FFF755FFEDE720222946204601F0E3 +:1026B000B9FC10B920352034F0E72B4605F1200293 +:1026C0001F68791CDDD104339A42F9D105F17843B2 +:1026D0001B481C4EB3F5801F1B4B38BF184603F137 +:1026E000F80332BFD946D1461E46FFF701FF076007 +:1026F000A5EB040C336804F11C0143F002033360C2 +:10270000231FD9F8007017F00507FAD153F8042FEA +:102710008B424CF80320F4D1BFF34F8FFFF7E8FE54 +:102720004FF0FF332022214603602846336823F010 +:102730000203336001F076FC0028BBD03846B0E7D6 +:10274000142100520C20005214200052102000527C +:102750001021005210B5084C237828B11BB9FFF79F +:10276000D5FE0123237010BD002BFCD02070BDE8E6 +:102770001040FFF7EDBE00BFE64100200244074BCA +:10278000D2B210B5904200D110BD441C00B253F833 +:10279000200041F8040BE0B2F4E700BF50400058BD +:1027A0000E4B30B51C6F240405D41C6F1C671C6FC6 +:1027B00044F400441C670A4C02442368D2B243F438 +:1027C00080732360074B904200D130BD441C51F808 +:1027D000045B00B243F82050E0B2F4E70044025832 +:1027E000004802585040005807B5012201A90020B6 +:1027F000FFF7C4FF019803B05DF804FB13B504466E +:10280000FFF7F2FFA04205D0012201A900200194A8 +:10281000FFF7C6FF02B010BD0144BFF34F8F064B58 +:10282000884204D3BFF34F8FBFF36F8F7047C3F855 +:102830005C022030F4E700BF00ED00E0034B1A68B3 +:102840001AB9034AD2F8D0241A607047E841002030 +:102850000040025808B5FFF7F1FF024B1868C0F3BB +:10286000806008BDE8410020EFF309830549683323 +:102870004A6B22F001024A6383F30988002383F341 +:102880001188704700EF00E0302080F3118862B6B5 +:102890000D4B0E4AD96821F4E0610904090C0A4382 +:1028A0000B49DA60D3F8FC2042F08072C3F8FC20B8 +:1028B000084AC2F8B01F116841F0010111602022DE +:1028C000DA7783F82200704700ED00E00003FA0594 +:1028D00055CEACC5001000E0302310B583F311884D +:1028E0000E4B5B6813F4006314D0F1EE103AEFF373 +:1028F00009844FF08073683CE361094BDB6B23660E +:1029000084F30988FFF7BCFA10B1064BA36110BD30 +:10291000054BFBE783F31188F9E700BF00ED00E00A +:1029200000EF00E02F0400083204000870B5BFF388 +:102930004F8FBFF36F8F1A4A0021C2F85012BFF3B6 +:102940004F8FBFF36F8F536943F400335361BFF36D +:102950004F8FBFF36F8FC2F88410BFF34F8FD2F841 +:10296000803043F6E074C3F3C900C3F34E335B0118 +:1029700003EA0406014646EA81750139C2F860524D +:10298000F9D2203B13F1200FF2D1BFF34F8F5369DF +:1029900043F480335361BFF34F8FBFF36F8F70BD2C +:1029A00000ED00E0FEE70000214B2248224A70B50E +:1029B000904237D3214BC11EDA1C121A22F00302B7 +:1029C0008B4238BF00220021FEF764FA1C4A002324 +:1029D000C2F88430BFF34F8FD2F8803043F6E074F2 +:1029E000C3F3C900C3F34E335B0103EA0406014697 +:1029F00046EA81750139C2F86C52F9D2203B13F1D5 +:102A0000200FF2D1BFF34F8FBFF36F8FBFF34F8F04 +:102A1000BFF36F8F0023C2F85032BFF34F8FBFF365 +:102A20006F8F70BD53F8041B40F8041BC0E700BF54 +:102A3000C4440008BC430020BC430020BC43002029 +:102A400000ED00E0074BD3F8D81021EA0001C3F8ED +:102A5000D810D3F8002122EA0002C3F80021D3F8ED +:102A6000003170470044025870B5D0E92443002279 +:102A70004FF0FF359E6804EB42135101D3F8000973 +:102A8000002805DAD3F8000940F08040C3F80009B7 +:102A9000D3F8000B002805DAD3F8000B40F0804093 +:102AA000C3F8000B013263189642C3F80859C3F803 +:102AB000085BE0D24FF00113C4F81C3870BD000071 +:102AC000890141F02001016103699B06FCD41220B9 +:102AD000FFF70EBA10B50A4C2046FEF7D1FE094B9F +:102AE000C4F89030084BC4F89430084C2046FEF7E8 +:102AF000C7FE074BC4F89030064BC4F8943010BDA5 +:102B0000EC410020000008400C43000888420020EF +:102B1000000004401843000870B503780546012BF7 +:102B20005CD1434BD0F89040984258D1414B0E2194 +:102B30006520D3F8D82042F00062C3F8D820D3F83B +:102B4000002142F00062C3F80021D3F80021D3F83D +:102B5000802042F00062C3F88020D3F8802022F069 +:102B60000062C3F88020D3F88030FEF7B5FC324B0A +:102B7000E360324BC4F800380023D5F89060C4F805 +:102B8000003EC02323604FF40413A3633369002B7A +:102B9000FCDA01230C203361FFF7AAF93369DB0764 +:102BA000FCD41220FFF7A4F93369002BFCDA0026CD +:102BB0002846A660FFF758FF6B68C4F81068DB680A +:102BC000C4F81468C4F81C6883BB1D4BA3614FF0A4 +:102BD000FF336361A36843F00103A36070BD194B29 +:102BE0009842C9D1134B4FF08060D3F8D82042F0FF +:102BF0000072C3F8D820D3F8002142F00072C3F865 +:102C00000021D3F80021D3F8802042F00072C3F8ED +:102C10008020D3F8802022F00072C3F88020D3F8FF +:102C20008030FFF70FFF0E214D209EE7064BCDE7CA +:102C3000EC410020004402584014004003002002F0 +:102C4000003C30C088420020083C30C0F8B5D0F8C5 +:102C50009040054600214FF000662046FFF730FF08 +:102C6000D5F8941000234FF001128F684FF0FF3019 +:102C7000C4F83438C4F81C2804EB431201339F42D3 +:102C8000C2F80069C2F8006BC2F80809C2F8080B64 +:102C9000F2D20B68D5F89020C5F898306362102303 +:102CA0001361166916F01006FBD11220FFF720F908 +:102CB000D4F8003823F4FE63C4F80038A36943F461 +:102CC000402343F01003A3610923C4F81038C4F86B +:102CD00014380B4BEB604FF0C043C4F8103B094B6A +:102CE000C4F8003BC4F81069C4F80039D5F898302E +:102CF00003F1100243F48013C5F89820A362F8BDD5 +:102D0000E842000840800010D0F8902090F88A1027 +:102D1000D2F8003823F4FE6343EA0113C2F8003806 +:102D2000704700002DE9F84300EB8103D0F8905084 +:102D30000C468046DA680FFA81F94801166806F0F9 +:102D40000306731E022B05EB41134FF0000194BFE5 +:102D5000B604384EC3F8101B4FF0010104F1100304 +:102D600098BF06F1805601FA03F3916998BF06F502 +:102D7000004600293AD0578A04F1580137434901E7 +:102D80006F50D5F81C180B430021C5F81C382B18C0 +:102D90000127C3F81019A7405369611E9BB3138A1A +:102DA000928B9B08012A88BF5343D8F89820981823 +:102DB00042EA034301F140022146C8F89800284640 +:102DC00005EB82025360FFF77BFE08EB8900C368C6 +:102DD0001B8A43EA845348341E4364012E51D5F8BC +:102DE0001C381F43C5F81C78BDE8F88305EB49176C +:102DF000D7F8001B21F40041C7F8001BD5F81C18B8 +:102E000021EA0303C0E704F13F030B4A28462146A9 +:102E100005EB83035A60FFF753FE05EB4910D0F82A +:102E2000003923F40043C0F80039D5F81C3823EAF0 +:102E30000707D7E70080001000040002D0F89420B4 +:102E40001268C0F89820FFF70FBE00005831D0F884 +:102E5000903049015B5813F4004004D013F4001F74 +:102E60000CBF0220012070474831D0F89030490152 +:102E70005B5813F4004004D013F4001F0CBF022071 +:102E80000120704700EB8101CB68196A0B68136061 +:102E90004B6853607047000000EB810330B5DD687C +:102EA000AA691368D36019B9402B84BF402313600B +:102EB0006B8A1468D0F890201C4402EB4110013C4E +:102EC00009B2B4FBF3F46343033323F0030343EA8F +:102ED000C44343F0C043C0F8103B2B6803F0030326 +:102EE000012B0ED1D2F8083802EB411013F4807F89 +:102EF000D0F8003B14BF43F0805343F00053C0F8B8 +:102F0000003B02EB4112D2F8003B43F00443C2F80D +:102F1000003B30BD2DE9F041D0F8906005460C46ED +:102F200006EB4113D3F8087B3A07C3F8087B08D5B2 +:102F3000D6F814381B0704D500EB8103DB685B6807 +:102F40009847FA071FD5D6F81438DB071BD505EBD1 +:102F50008403D968CCB98B69488A5A68B2FBF0F609 +:102F600000FB16228AB91868DA6890420DD2121A4C +:102F7000C3E90024302383F3118821462846FFF754 +:102F80008BFF84F31188BDE8F081012303FA04F27A +:102F90006B8923EA02036B81CB68002BF3D02146B7 +:102FA0002846BDE8F041184700EB81034A0170B59F +:102FB000DD68D0F890306C692668E66056BB1A442C +:102FC0004FF40020C2F810092A6802F00302012A17 +:102FD0000AB20ED1D3F8080803EB421410F4807F34 +:102FE000D4F8000914BF40F0805040F00050C4F8FD +:102FF000000903EB4212D2F8000940F00440C2F885 +:1030000000090122D3F8340802FA01F10143C3F8A0 +:10301000341870BD19B9402E84BF4020206020684C +:103020001A442E8A8419013CB4FBF6F440EAC440E9 +:1030300040F00050C6E700002DE9F843D0F890605A +:1030400005460C464F0106EB4113D3F8088918F0EA +:10305000010FC3F808891CD0D6F81038DB0718D543 +:1030600000EB8103D3F80CC0DCF81430D3F800E097 +:10307000DA68964530D2A2EB0E024FF000091A60D2 +:10308000C3F80490302383F31188FFF78DFF89F391 +:10309000118818F0800F1DD0D6F834380126A640CC +:1030A000334217D005EB84030134D5F89050D3F8A0 +:1030B0000CC0E4B22F44DCF8142005EB0434D2F841 +:1030C00000E05168714514D3D5F8343823EA060678 +:1030D000C5F83468BDE8F883012303FA01F20389D7 +:1030E00023EA02030381DCF80830002BD1D0984793 +:1030F000CFE7AEEB0103BCF81000834228BF0346C4 +:10310000D7F8180980B2B3EB800FE3D89068A0F12C +:10311000040959F8048FC4F80080A0EB090898440A +:10312000B8F1040FF5D818440B4490605360C8E719 +:103130002DE9F84FD0F8905004466E69AB691E40F7 +:1031400016F480586E6103D0BDE8F84FFEF708BC56 +:10315000002E12DAD5F8003E9B0705D0D5F8003EC8 +:1031600023F00303C5F8003ED5F80438204623F0C9 +:103170000103C5F80438FEF721FC370505D52046C4 +:10318000FFF772FC2046FEF707FCB0040CD5D5F81B +:10319000083813F0060FEB6823F470530CBF43F4A8 +:1031A000105343F4A053EB6031071BD56368DB6811 +:1031B0001BB9AB6923F00803AB612378052B0CD155 +:1031C000D5F8003E9A0705D0D5F8003E23F003035A +:1031D000C5F8003E2046FEF7F1FB6368DB680BB1E3 +:1031E00020469847F30200F1BA80B70226D5D4F8FA +:1031F000909000274FF0010A09EB4712D2F8003BEC +:1032000003F44023B3F5802F11D1D2F8003B002BFB +:103210000DDA62890AFA07F322EA0303638104EBF9 +:103220008703DB68DB6813B13946204698470137CE +:10323000D4F89430FFB29B689F42DDD9F00619D5CF +:10324000D4F89000026AC2F30A1702F00F0302F4E6 +:10325000F012B2F5802F00F0CA80B2F5402F09D1EC +:1032600004EB8303002200F58050DB681B6A974261 +:1032700040F0B0803003D5F8185835D5E90303D5B0 +:1032800000212046FFF746FEAA0303D50121204670 +:10329000FFF740FE6B0303D502212046FFF73AFEFD +:1032A0002F0303D503212046FFF734FEE80203D5A0 +:1032B00004212046FFF72EFEA90203D50521204652 +:1032C000FFF728FE6A0203D506212046FFF722FEFB +:1032D0002B0203D507212046FFF71CFEEF0103D583 +:1032E00008212046FFF716FE700340F1A780E9078A +:1032F00003D500212046FFF79FFEAA0703D5012131 +:103300002046FFF799FE6B0703D502212046FFF701 +:1033100093FE2F0703D503212046FFF78DFEEE060F +:1033200003D504212046FFF787FEA80603D5052113 +:103330002046FFF781FE690603D506212046FFF7E8 +:103340007BFE2A0603D507212046FFF775FEEB0515 +:1033500074D520460821BDE8F84FFFF76DBED4F8BC +:1033600090904FF0000B4FF0010AD4F894305FFAC0 +:103370008BF79B689F423FF638AF09EB4713D3F8B2 +:10338000002902F44022B2F5802F20D1D3F8002981 +:10339000002A1CDAD3F8002942F09042C3F8002931 +:1033A000D3F80029002AFBDB3946D4F89000FFF758 +:1033B00087FB22890AFA07F322EA0303238104EB3D +:1033C0008703DB689B6813B13946204698470BF1A9 +:1033D000010BCAE7910701D1D0F80080072A02F15A +:1033E00001029CBF03F8018B4FEA18283FE704EB6A +:1033F000830300F58050DA68D2F818C0DCF80820A2 +:10340000DCE9001CA1EB0C0C00218F4208D1DB6829 +:103410009B699A683A449A605A683A445A6029E724 +:1034200011F0030F01D1D0F800808C4501F10101AA +:1034300084BF02F8018B4FEA1828E6E7BDE8F88F51 +:1034400008B50348FFF774FEBDE80840FFF744BA2B +:10345000EC41002008B50348FFF76AFEBDE80840CC +:10346000FFF73ABA88420020D0F8903003EB4111C0 +:10347000D1F8003B43F40013C1F8003B7047000053 +:10348000D0F8903003EB4111D1F8003943F4001328 +:10349000C1F8003970470000D0F8903003EB4111BB +:1034A000D1F8003B23F40013C1F8003B7047000043 +:1034B000D0F8903003EB4111D1F8003923F4001318 +:1034C000C1F800397047000030B50433039C017225 +:1034D000002104FB0325C160C0E90653049B03637C +:1034E000059BC0E90000C0E90422C0E90842C0E928 +:1034F0000A11436330BD00000022416AC260C0E986 +:103500000411C0E90A226FF00101FEF761BD00005D +:10351000D0E90432934201D1C2680AB9181D70473C +:1035200000207047036919600021C2680132C2603F +:10353000C269134482699342036124BF436A0361F1 +:10354000FEF73ABD38B504460D46E3683BB1626903 +:103550000020131D1268A3621344E36207E0237A7C +:1035600033B929462046FEF717FD0028EDDA38BDAD +:103570006FF00100FBE70000C368C269013BC36054 +:103580004369134482699342436124BF436A4361A0 +:1035900000238362036B03B11847704770B5302373 +:1035A000044683F31188866A3EB9FFF7CBFF0546D0 +:1035B00018B186F31188284670BDA36AE26A13F831 +:1035C000015B9342A36202D32046FFF7D5FF00239D +:1035D00083F31188EFE700002DE9F84F04460E460B +:1035E000174698464FF0300989F311880025AA46FE +:1035F000D4F828B0BBF1000F09D141462046FFF7AF +:10360000A1FF20B18BF311882846BDE8F88FD4E9DB +:103610000A12A7EB050B521A934528BF9346BBF13C +:10362000400F1BD9334601F1400251F8040B91427F +:1036300043F8040BF9D1A36A403640354033A36206 +:10364000D4E90A239A4202D32046FFF795FF8AF372 +:103650001188BD42D8D289F31188C9E730465A464D +:10366000FDF7F2FBA36A5E445D445B44A362E7E7B7 +:1036700010B5029C0433017203FB0421C460C0E94D +:1036800006130023C0E90A33039B0363049BC0E9CC +:103690000000C0E90422C0E90842436310BD0000F5 +:1036A000026A6FF00101C260426AC0E9042200228E +:1036B000C0E90A22FEF78CBCD0E904239A4201D16A +:1036C000C26822B9184650F8043B0B6070470023CB +:1036D0001846FAE7C3680021C2690133C360436931 +:1036E000134482699342436124BF436A4361FEF7F6 +:1036F00063BC000038B504460D46E3683BB123695E +:1037000000201A1DA262E2691344E36207E0237AF3 +:1037100033B929462046FEF73FFC0028EDDA38BDD4 +:103720006FF00100FBE7000003691960C268013A0D +:10373000C260C269134482699342036124BF436A31 +:10374000036100238362036B03B1184770470000D5 +:1037500070B530230D460446114683F31188866AFE +:103760002EB9FFF7C7FF10B186F3118870BDA36AA9 +:103770001D70A36AE26A01339342A36204D3E16934 +:1037800020460439FFF7D0FF002080F31188EDE7D1 +:103790002DE9F84F04460D46904699464FF0300A01 +:1037A0008AF311880026B346A76A4FB949462046D6 +:1037B000FFF7A0FF20B187F311883046BDE8F88FEE +:1037C000D4E90A073A1AA8EB0607974228BF17461A +:1037D000402F1BD905F1400355F8042B9D4240F8BA +:1037E000042BF9D1A36A40364033A362D4E90A23FB +:1037F0009A4204D3E16920460439FFF795FF8BF321 +:1038000011884645D9D28AF31188CDE729463A4630 +:10381000FDF71AFBA36A3D443E443B44A362E5E73F +:10382000D0E904239A4217D1C3689BB1836A8BB154 +:10383000043B9B1A0ED01360C368013BC360C3698D +:103840001A4483699A42026124BF436A03610023D8 +:1038500083620123184670470023FBE700F024B978 +:10386000014B586A704700BF000C0040034B002218 +:1038700058631A610222DA60704700BF000C0040F2 +:10388000014B0022DA607047000C0040014B586386 +:10389000704700BF000C0040FEE7000070B51B4BF6 +:1038A0000025044686B058600E4685620163FEF727 +:1038B000EBFF04F11003A560E562C4E904334FF0A7 +:1038C000FF33C4E90044C4E90635FFF7C9FF2B46BE +:1038D000024604F134012046C4E9082380230C4A3F +:1038E0002565FEF70FFB01230A4AE060009203758D +:1038F000684672680192B268CDE90223064BCDE9B1 +:103900000435FEF727FB06B070BD00BFA8260020D7 +:10391000244300082943000899380008024AD36A62 +:103920001843D062704700BF402400204B684360BA +:103930008B688360CB68C3600B6943614B6903622A +:103940008B6943620B6803607047000008B53C4B0D +:1039500040F2FF713B48D3F888200A43C3F888201F +:10396000D3F8882022F4FF6222F00702C3F88820EF +:10397000D3F88820D3F8E0200A43C3F8E020D3F836 +:1039800008210A43C3F808212F4AD3F80831114609 +:10399000FFF7CCFF00F5806002F11C01FFF7C6FFC6 +:1039A00000F5806002F13801FFF7C0FF00F580608C +:1039B00002F15401FFF7BAFF00F5806002F17001D7 +:1039C000FFF7B4FF00F5806002F18C01FFF7AEFF56 +:1039D00000F5806002F1A801FFF7A8FF00F5806004 +:1039E00002F1C401FFF7A2FF00F5806002F1E001DF +:1039F000FFF79CFF00F5806002F1FC01FFF796FFE6 +:103A000002F58C7100F58060FFF790FF00F018F967 +:103A10000E4BD3F8902242F00102C3F89022D3F863 +:103A2000942242F00102C3F894220522C3F89820A0 +:103A30004FF06052C3F89C20054AC3F8A02008BD8F +:103A400000440258000002583043000800ED00E036 +:103A50001F00080308B500F0C7FAFEF731FA0F4B54 +:103A6000D3F8DC2042F04002C3F8DC20D3F8042174 +:103A700022F04002C3F80421D3F80431084B1A683D +:103A800042F008021A601A6842F004021A60FEF757 +:103A9000D5FEBDE80840FEF787BC00BF00440258D1 +:103AA0000018024870470000114BD3F8E82042F09C +:103AB0000802C3F8E820D3F8102142F00802C3F846 +:103AC00010210C4AD3F81031D36B43F00803D363B1 +:103AD000C722094B9A624FF0FF32DA6200229A61E4 +:103AE0005A63DA605A6001225A611A60704700BF57 +:103AF000004402580010005C000C0040094A08B560 +:103B00001169D3680B40D9B29B076FEA01011161BB +:103B100007D5302383F31188FEF7E8F9002383F3F8 +:103B2000118808BD000C0040064BD3F8DC2002438E +:103B3000C3F8DC20D3F804211043C3F80401D3F800 +:103B4000043170470044025808B53C4B4FF0FF3138 +:103B5000D3F8802062F00042C3F88020D3F88020A0 +:103B600002F00042C3F88020D3F88020D3F88420EC +:103B7000C3F88410D3F884200022C3F88420D3F83B +:103B80008400D86F40F0FF4040F4FF0040F4DF4075 +:103B900040F07F00D867D86F20F0FF4020F4FF008E +:103BA00020F4DF4020F07F00D867D86FD3F888007A +:103BB0006FEA40506FEA5050C3F88800D3F888008D +:103BC000C0F30A00C3F88800D3F88800D3F8900047 +:103BD000C3F89010D3F89000C3F89020D3F8900069 +:103BE000D3F89400C3F89410D3F89400C3F8942049 +:103BF000D3F89400D3F89800C3F89810D3F898003D +:103C0000C3F89820D3F89800D3F88C00C3F88C1030 +:103C1000D3F88C00C3F88C20D3F88C00D3F89C0028 +:103C2000C3F89C10D3F89C10C3F89C20D3F89C30A8 +:103C3000FDF776FBBDE8084000F0AEB9004402583D +:103C400008B50122534BC3F80821534BD3F8F42095 +:103C500042F00202C3F8F420D3F81C2142F0020221 +:103C6000C3F81C210222D3F81C314C4BDA605A688D +:103C70009104FCD54A4A1A6001229A60494ADA60E6 +:103C800000221A614FF440429A61444B9A699204AF +:103C9000FCD51A6842F480721A603F4B1A6F12F416 +:103CA000407F04D04FF480321A6700221A671A68E6 +:103CB00042F001021A60384B1A685007FCD5002206 +:103CC0001A611A6912F03802FBD1012119604FF014 +:103CD000804159605A67344ADA62344A1A611A6874 +:103CE00042F480321A602C4B1A689103FCD51A6892 +:103CF00042F480521A601A689204FCD52C4A2D496D +:103D00009A6200225A63196301F57C01DA6301F2B9 +:103D1000E71199635A64284A1A64284ADA621A68D1 +:103D200042F0A8521A601C4B1A6802F02852B2F1F5 +:103D3000285FF9D148229A614FF48862DA61402203 +:103D40001A621F4ADA641F4A1A651F4A5A651F4AD7 +:103D50009A6532231E4A1360136803F00F03022B87 +:103D6000FAD10D4A136943F003031361136903F099 +:103D70003803182BFAD14FF00050FFF7D5FE4FF063 +:103D80008040FFF7D1FE4FF00040BDE80840FFF74C +:103D9000CBBE00BF008000510044025800480258CA +:103DA00000C000F0020000010000FF010088900840 +:103DB0001210200063020901470E0508DD0BBF0148 +:103DC00020000020000001100910E0000001011097 +:103DD000002000524FF0B04208B5D2F8883003F00E +:103DE0000103C2F8883023B1044A13680BB150684C +:103DF0009847BDE80840FEF76FBD00BF3C43002078 +:103E00004FF0B04208B5D2F8883003F00203C2F890 +:103E1000883023B1044A93680BB1D0689847BDE855 +:103E20000840FEF759BD00BF3C4300204FF0B042B0 +:103E300008B5D2F8883003F00403C2F8883023B103 +:103E4000044A13690BB150699847BDE80840FEF772 +:103E500043BD00BF3C4300204FF0B04208B5D2F84C +:103E6000883003F00803C2F8883023B1044A93690C +:103E70000BB1D0699847BDE80840FEF72DBD00BFE3 +:103E80003C4300204FF0B04208B5D2F8883003F030 +:103E90001003C2F8883023B1044A136A0BB1506A88 +:103EA0009847BDE80840FEF717BD00BF3C4300201F +:103EB0004FF0B04310B5D3F8884004F47872C3F8DB +:103EC0008820A30604D5124A936A0BB1D06A98479A +:103ED000600604D50E4A136B0BB1506B9847210650 +:103EE00004D50B4A936B0BB1D06B9847E20504D510 +:103EF000074A136C0BB1506C9847A30504D5044ACC +:103F0000936C0BB1D06C9847BDE81040FEF7E4BC51 +:103F10003C4300204FF0B04310B5D3F8884004F480 +:103F20007C42C3F88820620504D5164A136D0BB194 +:103F3000506D9847230504D5124A936D0BB1D06D8F +:103F40009847E00404D50F4A136E0BB1506E9847A2 +:103F5000A10404D50B4A936E0BB1D06E984762044E +:103F600004D5084A136F0BB1506F9847230404D54A +:103F7000044A936F0BB1D06F9847BDE81040FEF72D +:103F8000ABBC00BF3C43002008B5FFF7B7FDBDE860 +:103F90000840FEF7A1BC0000062108B50846FDF761 +:103FA0009BFA06210720FDF797FA06210820FDF766 +:103FB00093FA06210920FDF78FFA06210A20FDF762 +:103FC0008BFA06211720FDF787FA06212820FDF736 +:103FD00083FA09217A20FDF77FFA07213220BDE814 +:103FE0000840FDF779BA000008B5FFF7ADFD00F015 +:103FF0000BF8FDF743FCFDF715FBFFF753FDBDE89C +:104000000840FFF72BBC00000023054A1946013386 +:10401000102BC2E9001102F10802F8D1704700BF6D +:104020003C43002010B501390244904201D10020E8 +:1040300005E0037811F8014FA34201D0181B10BD11 +:104040000130F2E7034611F8012B03F8012B002A97 +:10405000F9D1704753544D333248373F3F3F0053F7 +:10406000544D3332483733782F3732780053544D1C +:104070003332483734332F3735332F37353000005C +:1040800001105A0003105900012058000320560067 +:1040900010000240080002400008024000000B002F +:1040A00028000240080002400408024006010C00FB +:1040B00040000240080002400808024010020D00C3 +:1040C00058000240080002400C08024016030E008F +:1040D000700002400C0002401008024000040F0073 +:1040E000880002400C00024014080240060510003F +:1040F000A00002400C000240180802401006110007 +:10410000B80002400C0002401C08024016072F00B5 +:104110001004024008040240200802400008380051 +:10412000280402400804024024080240060939001D +:10413000400402400804024028080240100A3A00E5 +:1041400058040240080402402C080240160B3B00B1 +:10415000700402400C04024030080240000C3C0095 +:10416000880402400C04024034080240060D44005A +:10417000A00402400C04024038080240100E450022 +:10418000B80402400C0402403C080240160F4600EE +:1041900000000000A11500088D150008C9150008D1 +:1041A000B5150008C1150008AD15000899150008DF +:1041B00085150008D515000800000000010000006A +:1041C0000000000063300000C44100089824002073 +:1041D000A82600204172647550696C6F74002542F6 +:1041E0004F415244252D424C002553455249414CE4 +:1041F000250000000200000000000000C1170008B8 +:104200003118000840004000583F0020683F00205F +:104210000200000000000000030000000000000099 +:10422000791800080000000010000000783F00200E +:10423000000000000100000000000000EC41002030 +:10424000010102004523000855220008F122000860 +:10425000D5220008430000005C4200080902430028 +:10426000020100C03209040000010202010005241D +:1042700000100105240100010424020205240600A7 +:1042800001070582030800FF09040100020A00007B +:104290000007050102400000070581024000000000 +:1042A00012000000A84200081201100102000040A4 +:1042B000091241570002010203010000040309042E +:1042C00025424F4152442500426C69747A57696E09 +:1042D0006748373433003031323334353637383984 +:1042E000414243444546000000000000D519000843 +:1042F0008D1C0008391D00084000400024430020A8 +:10430000244300200100000034430020800000000E +:104310004001000008000000000100000010000043 +:10432000080000006D61696E0069646C6500000042 +:104330000000812A00000000AAAAAAAA0000002406 +:10434000FFFE00000000000000A00A0000000001C5 +:1043500000000000AAAAAAAA00000001FFFF0000B6 +:10436000000000000000000000000040000000000D +:10437000AAAAAAAA00000040FFFF00000000000057 +:10438000000000000000100000000000AAAAAAAA75 +:1043900000000000FFFF000000000000000000001F +:1043A0000000400000000000AAAAAAAA00004000E5 +:1043B000FFFF0000000000000000000000000000FF +:1043C00000000000AAAAAAAA00000000FFFF000047 +:1043D00000000000000000000000000000000000DD +:1043E000AAAAAAAA00000000FFFF00000000000027 +:1043F000000000000000000000000000AAAAAAAA15 +:1044000000000000FFFF00000000000000000000AE +:104410000000000000000000AAAAAAAA00000000F4 +:10442000FFFF00000000000000000000000000008E +:1044300000000000AAAAAAAA00000000FFFF0000D6 +:10444000000000000000000000000000000000006C +:10445000AAAAAAAA00000000FFFF000000000000B6 +:1044600000000000000000009004000000000000B8 +:1044700000001A0000000000FF0000000000000023 +:1044800054400008830400005F400008500400000E +:104490006D40000800960000000008009600000033 +:1044A0000008000004000000BC42000800000000FA +:1044B00000000000000000000000000000000000FC +:0444C00000000000F8 +:00000001FF diff --git a/Tools/bootloaders/FoxeerF405v2_bl.bin b/Tools/bootloaders/FoxeerF405v2_bl.bin new file mode 100644 index 0000000000000..ad29c5deccbdf Binary files /dev/null and b/Tools/bootloaders/FoxeerF405v2_bl.bin differ diff --git a/Tools/bootloaders/FoxeerF405v2_bl.hex b/Tools/bootloaders/FoxeerF405v2_bl.hex new file mode 100644 index 0000000000000..3a11e71c6a774 --- /dev/null +++ b/Tools/bootloaders/FoxeerF405v2_bl.hex @@ -0,0 +1,894 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E30100086D2F000868 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E3010008153200083D32000802 +:10006000653200088D320008B5320008E30100084F +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008DD32000885 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000B1330008E3010008E3010008E301000890 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E00041330008E3010008E3010008E3010008D0 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E3010008212700089B +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F030FF41 +:1002500002F02AFE4FF055301F491B4A91423CBF25 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F00EFF02F058FEF4 +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F0F6BE000600200022002072 +:1002D0000000000808ED00E00000002000060020FB +:1002E0007837000800220020402200204022002011 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F072FAFEE701F08C +:1003300001FA00DFFEE7000038B500F0BBFB01F07A +:1003400087FE054601F0AAFE0446C8B90E4B9D4241 +:1003500018D001339D4218BF044641F2883504BFCE +:1003600001240025002001F07DFE0CB100F074F89E +:1003700000F000FD284600F0BFF800F06DF8F9E746 +:100380000025EFE70546EDE7010007B008B500F0EE +:1003900063FBA0F120035842584108BD07B541F264 +:1003A0001203022101A8ADF8043000F073FB03B082 +:1003B0005DF804FB38B5302383F3118817480368D0 +:1003C0000BB101F0F1FA164A144800234FF47A7188 +:1003D00001F0E0FA002383F31188124C236813B173 +:1003E0002368013B2360636813B16368013B63606A +:1003F0000D4D2B7833B963687BB9022000F024FCE3 +:10040000322363602B78032B07D163682BB902205A +:1004100000F01AFC4FF47A73636038BD402200206C +:10042000B50300086023002058220020084B1870F4 +:1004300003280CD8DFE800F008050208022000F0CD +:10044000F9BB022000F0ECBB024B00225A6070475F +:100450005822002060230020234B244A10B51C465C +:10046000196801313FD004339342F9D16268A24246 +:1004700039D31F4B9B6803F1006303F540439A4255 +:1004800031D2002000F030FB0220FFF7CFFF194BE4 +:100490001A6C00221A64196E1A66196E596C5A6425 +:1004A000596E5A665A6E5A6942F080025A615A6908 +:1004B00022F080025A615A691A6942F000521A61A8 +:1004C0001A6922F000521A611B6972B64FF0E023DC +:1004D0003021C3F8084DD4E9003281F311889D46DC +:1004E00083F30888104710BD00C0000820C0000832 +:1004F00000220020003802402DE9F04F93B0AA4BB3 +:1005000000902022FF210AA89D6800F0DDFBA74A89 +:100510001378A3B9A648012103601170302383F337 +:10052000118803680BB101F03FFAA24AA0480023EA +:100530004FF47A7101F02EFA002383F31188009BA7 +:1005400013B19D4B009A1A609C4A009C1378032BB0 +:100550001EBF00231370984A4FF0000A18BF536063 +:10056000D3465646D146012000F064FB24B1924B9D +:100570001B68002B00F01182002000F06DFA039040 +:10058000039B002BF2DB012000F04AFB039B213B85 +:10059000162BE8D801A252F823F000BFF905000895 +:1005A00021060008B5060008670500086705000871 +:1005B000670500083F0700080F0900082908000820 +:1005C0008B080008B3080008D90800086705000870 +:1005D000EB080008670500085D0900089906000897 +:1005E00067050008A109000805060008990600082B +:1005F000670500088B0800080220FFF7C7FE0028E7 +:1006000040F0F581009B0221BAF1000F08BF1C46A3 +:1006100005A841F21233ADF8143000F03BFAA2E71E +:100620004FF47A7000F018FA071EEBDB0220FFF798 +:10063000ADFE0028E6D0013F052F00F2DA81DFE8A9 +:1006400007F0030A0D10133605230593042105A8AE +:1006500000F020FA17E054480421F9E75848042133 +:10066000F6E758480421F3E74FF01C08404600F035 +:100670003DFA08F104080590042105A800F00AFAE3 +:10068000B8F12C0FF2D1012000FA07F747EA0B0B63 +:100690005FFA8BFB4FF0000900F062FB26B10BF014 +:1006A0000B030B2B08BF0024FFF778FE5BE74648DF +:1006B0000421CDE7002EA5D00BF00B030B2BA1D10D +:1006C0000220FFF763FE074600289BD0012000F0C0 +:1006D0000BFA0220FFF7AAFE00261FFA86F8404612 +:1006E00000F012FA044690B10021404600F01CFAD6 +:1006F00001360028F1D1BA46044641F21213022114 +:1007000005A8ADF814303E4600F0C4F92BE70120EF +:10071000FFF78CFE2546244B9B68AB4207D9284641 +:1007200000F0E4F9013040F067810435F3E7234B32 +:1007300000251D70204BBA465D603E46ACE7002E9A +:100740003FF460AF0BF00B030B2B7FF45BAF022089 +:10075000FFF76CFE322000F07FF9B0F10008FFF6E1 +:1007600051AF18F003077FF44DAF0F4A926808EBC2 +:10077000050393423FF646AFB8F5807F3FF742AF9F +:10078000124B0193B84523DD4FF47A7000F064F901 +:100790000390039A002AFFF635AF019B039A03F8F2 +:1007A000012B0137EDE700BF002200205C23002071 +:1007B00040220020B50300086023002058220020BA +:1007C00004220020082200200C2200205C220020AD +:1007D000C820FFF7DBFD074600283FF413AF1F2DAD +:1007E00011D8C5F1200242450AAB25F0030028BF0D +:1007F000424683490192184400F040FA019A804829 +:10080000FF2100F061FA4FEAA8037D490193C8F384 +:100810008702284600F060FA064600283FF46DAFD4 +:10082000019B05EB830537E70220FFF7AFFD0028AA +:100830003FF4E8AE00F0A4F900283FF4E3AE00274F +:10084000B846704B9B68BB4218D91F2F11D80A9B22 +:1008500001330ED027F0030312AA134453F8203CAF +:1008600005934046042205A900F0AEFA04378046FD +:10087000E7E7384600F03AF90590F2E7CDF8148042 +:10088000042105A800F006F906E70023642104A866 +:10089000049300F0F5F800287FF4B4AE0220FFF7CF +:1008A00075FD00283FF4AEAE049800F051F90590B4 +:1008B000E6E70023642104A8049300F0E1F800288F +:1008C0007FF4A0AE0220FFF761FD00283FF49AAE4E +:1008D000049800F04DF9EAE70220FFF757FD0028E1 +:1008E0003FF490AE00F05CF9E1E70220FFF74EFD27 +:1008F00000283FF487AE05A9142000F057F9042121 +:100900000746049004A800F0C5F83946B9E732203C +:1009100000F0A2F8071EFFF675AEBB077FF472AEBB +:10092000384A926807EB090393423FF66BAE022008 +:10093000FFF72CFD00283FF465AE27F003074F4476 +:10094000B9453FF4A9AE484600F0D0F8042105901F +:1009500005A800F09FF809F10409F1E74FF47A7057 +:10096000FFF714FD00283FF44DAE00F009F9002810 +:1009700044D00A9B01330BD008220AA9002000F0C2 +:10098000ABF900283AD02022FF210AA800F09CF9F8 +:10099000FFF704FD1C4800F041FF13B0BDE8F08FE5 +:1009A000002E3FF42FAE0BF00B030B2B7FF42AAE7F +:1009B0000023642105A8059300F062F8074600288B +:1009C0007FF420AE0220FFF7E1FC804600283FF4D0 +:1009D00019AEFFF7E3FC41F2883000F01FFF0598E5 +:1009E00000F0F0F9464600F0BBF93C46BBE5064690 +:1009F00052E64FF0000905E6BA467EE637467CE649 +:100A00005C22002000220020A086010070B50F4B60 +:100A10001B780133DBB2012B0C4611D80C4D296831 +:100A20004FF47A730E6AA2FB03320146224628462F +:100A3000B047844204D1074B00221A70012070BDD8 +:100A40004FF4FA7000F0EAFE0020F8E710220020D0 +:100A5000082600209423002007B500230246012128 +:100A60000DF107008DF80730FFF7D0FF20B19DF89A +:100A7000070003B05DF804FB4FF0FF30F9E700001A +:100A80000A4608B50421FFF7C1FF80F00100C0B29B +:100A9000404208BD30B4054C2368DD69044B0A466A +:100AA000AC460146204630BC604700BF0826002007 +:100AB000A086010070B501F0D1F9094E094D3080D2 +:100AC000002428683388834208D901F0C1F92B68D3 +:100AD00004440133B4F5404F2B60F2D370BD00BF26 +:100AE000962300206823002001F066BA00F1006020 +:100AF00000F540400068704700F10060920000F58A +:100B0000404001F0F1B90000054B1A68054B1B8805 +:100B10009B1A834202D9104401F09AB90020704711 +:100B2000682300209623002038B5084D044629B1DB +:100B300028682044BDE8384001F0AAB9286820445C +:100B400001F08EF90028F3D038BD00BF68230020E3 +:100B500010F003030AD1B0F5047F05D200F1005074 +:100B6000A0F51040D0F80038184670470023FBE786 +:100B700000F10050A0F51040D0F8100A70470000B6 +:100B8000064991F8243033B10023086A81F82430F3 +:100B90000822FFF7B1BF0120704700BF6C2300207F +:100BA000014B1868704700BF002004E070B5194B76 +:100BB0001D68194B0138C5F30B0408442D0C0422A1 +:100BC0001E88A6420BD15C680A46013C824213464D +:100BD0000FD214F9016F4EB102F8016BF6E7013A3A +:100BE00003F10803ECD181420B4602D22C2203F818 +:100BF000012B0A4A05241688AE4204D1984284BFCC +:100C0000967803F8016B013C02F10402F3D1581A03 +:100C100070BD00BF002004E0943400088034000858 +:100C2000022802BF024B4FF000529A61704700BF8A +:100C300000000240022802BF024B4FF400529A61AA +:100C4000704700BF00000240022801BF024A5369FA +:100C500083F40053536170470000024070B50446AE +:100C60004FF47A764CB1412C254628BF412506FB2E +:100C700005F000F0D3FD641BF4E770BD10B5002350 +:100C8000934203D0CC5CC4540133F9E710BD00009B +:100C900010B5013810F9013F3BB191F900409C4279 +:100CA00003D11AB10131013AF4E71AB191F90020E8 +:100CB000981A10BD1046FCE703460246D01A12F9F6 +:100CC000011B0029FAD1704702440346934202D027 +:100CD00003F8011BFAE770472DE9F8431F4D14464E +:100CE00095F824200746884652BBDFF870909CB3E5 +:100CF00095F824302BB92022FF2148462F62FFF7B8 +:100D0000E3FF95F82400C0F10802A24228BF224662 +:100D1000D6B24146920005EB8000FFF7AFFF95F891 +:100D20002430A41B1E44F6B2082E17449044E4B2AB +:100D300085F82460DBD1FFF723FF0028D7D108E036 +:100D40002B6A03EB82038342CFD0FFF719FF002801 +:100D5000CBD10020BDE8F8830120FBE76C23002005 +:100D6000024B1A78024B1A70704700BF9423002080 +:100D70001022002010B5104C104800F0B5F82146A4 +:100D80000E4800F0DDF82468626DD2F8043843F0B4 +:100D90000203C2F804384FF47A70FFF75FFF084986 +:100DA000204600F0D3F9626DD2F8043823F0020334 +:100DB000C2F8043810BD00BF6035000808260020C6 +:100DC000683500087047000030B5094D0A4491426B +:100DD0000DD011F8013B5840082340F30004013BBB +:100DE0002C4013F0FF0384EA5000F6D1EFE730BD4A +:100DF0002083B8ED026843681143016003B11847CE +:100E00007047000013B5446BD4F894341A68117815 +:100E1000042915D1217C022912D1197912890123C3 +:100E20008B4013420CD101A904F14C0001F0F8FEF3 +:100E3000D4F89444019B21790246206800F0D0F94F +:100E400002B010BD143001F07BBE00004FF0FF3344 +:100E5000143001F075BE00004C3001F04DBF0000B1 +:100E60004FF0FF334C3001F047BF0000143001F069 +:100E700049BE00004FF0FF31143001F043BE0000C6 +:100E80004C3001F019BF00004FF0FF324C3001F040 +:100E900013BF00000020704710B5D0F894341A68D2 +:100EA00011780429044617D1017C022914D15979FB +:100EB000528901238B4013420ED1143001F0DCFD26 +:100EC000024648B1D4F894444FF4807361792068A5 +:100ED000BDE8104000F072B910BD0000406BFFF794 +:100EE000DBBF0000704700007FB5124B036000239A +:100EF0004360C0E90233012502260F4B0574044606 +:100F00000290019300F18402294600964FF4807309 +:100F1000143001F08DFD094B0294CDE9006304F516 +:100F200023724FF48073294604F14C0001F054FE03 +:100F300004B070BDB4340008DD0E0008050E0008D2 +:100F40000B68302282F311880A7903EB82029061E8 +:100F50004A79093243F822008A7912B103EB8203FD +:100F600098610223C0F894140374002080F3118860 +:100F70007047000038B5037F044613B190F8543031 +:100F8000ABB9201D01250221FFF734FF04F1140045 +:100F900025776FF0010100F069FC84F8545004F1EA +:100FA0004C006FF00101BDE8384000F05FBC38BD77 +:100FB00010B5012104460430FFF71CFF00232377FE +:100FC00084F8543010BD000038B5044600251430B4 +:100FD00001F046FD04F14C00257701F015FE201DBF +:100FE00084F854500121FFF705FF2046BDE8384042 +:100FF000FFF752BF90F8443003F06003202B07D175 +:1010000090F84520212A4FF0000303D81F2A06D864 +:1010100000207047222AFBD1C0E90E3303E0034AC7 +:1010200082630722C26303640120704711220020FB +:1010300037B5D0F894341A681178042904461AD1C7 +:10104000017C022917D11979128901238B4013429F +:1010500011D100F14C05284601F096FE58B101A9C6 +:10106000284601F0DDFDD4F89444019B2179024625 +:10107000206800F0B5F803B030BD0000F0B500EB1B +:10108000810385B09E6904460D46FEB1302383F38B +:10109000118804EB8507301D0821FFF7ABFEFB68C4 +:1010A0005B691B6806F14C001BB1019001F0C6FDA5 +:1010B000019803A901F0B4FD024648B1039B2946FB +:1010C000204600F08DF8002383F3118805B0F0BDB1 +:1010D000FB685A691268002AF5D01B8A013B13404D +:1010E000F1D104F14402EAE7093138B550F8214062 +:1010F000DCB1302383F31188D4F894241368527937 +:1011000003EB8203DB689B695D6845B104216018CD +:10111000FFF770FE294604F1140001F0B7FC2046E9 +:10112000FFF7BAFE002383F3118838BD7047000033 +:1011300001F016B8012303700023C0E90133C36135 +:1011400083620362C36243620363704738B5044637 +:10115000302383F311880025C0E90355C0E9055504 +:10116000416001F00DF80223237085F311882846B1 +:1011700038BD000070B500EB810305465069DA60A8 +:101180000E46144618B110220021FFF79DFDA069FC +:1011900018B110220021FFF797FD31462846BDE81F +:1011A000704001F0B7B80000826802F0011282605E +:1011B0000022C0E90422826101F038B9F0B400EBEA +:1011C00081044789E4680125A4698D403D43458138 +:1011D00023600023A2606360F0BC01F053B90000FB +:1011E000F0B400EB81040789E468012564698D404F +:1011F0003D43058123600023A2606360F0BC01F0E1 +:10120000CDB9000070B50223002504460370C0E983 +:101210000255C0E90455C564856180F8345001F079 +:1012200015F863681B6823B129462046BDE8704065 +:10123000184770BD0378052B10B504460AD080F816 +:1012400050300523037043681B680BB10421984795 +:101250000023A36010BD00000178052906D190F895 +:101260005020436802701B6803B1184770470000A4 +:1012700070B590F83430044613B1002380F8343050 +:1012800004F14402204601F0F3F863689B68B3B9A7 +:1012900094F8443013F0600535D00021204601F069 +:1012A00093FB0021204601F085FB63681B6813B1A6 +:1012B000062120469847062384F8343070BD204626 +:1012C00098470028E4D0B4F84A30E26B9A4288BFCD +:1012D000E36394F94430E56B002B4FF0300380F268 +:1012E0000381002D00F0F280092284F8342083F37A +:1012F00011880021D4E90E232046FFF771FF002357 +:1013000083F31188DAE794F8452003F07F0343EA7A +:10131000022340F20232934200F0C58021D8B3F597 +:10132000807F48D00DD8012B3FD0022B00F0938056 +:10133000002BB2D104F14C02A2630222E2632364C7 +:10134000C1E7B3F5817F00F09B80B3F5407FA4D166 +:1013500094F84630012BA0D1B4F84C3043F002038E +:1013600032E0B3F5006F4DD017D8B3F5A06F31D090 +:10137000A3F5C063012B90D8636894F846205E689B +:1013800094F84710B4F848302046B047002884D07D +:101390004368A3630368E3631AE0B3F5106F36D0C4 +:1013A00040F6024293427FF478AF5C4BA363022382 +:1013B000E3630023C3E794F84630012B7FF46DAF5D +:1013C000B4F84C3023F00203C4E90E55A4F84C30B5 +:1013D000256478E7B4F84430B3F5A06F0ED194F8E3 +:1013E000463084F84E30204600F088FF63681B6862 +:1013F00013B1012120469847032323700023C4E939 +:101400000E339CE704F14F03A3630123C3E7237862 +:10141000042B10D1302383F311882046FFF7C4FE3C +:1014200085F311880321636884F84F5021701B688D +:101430000BB12046984794F84630002BDED084F854 +:101440004F300423237063681B68002BD6D0022121 +:1014500020469847D2E794F848301D0603F00F0164 +:1014600020460AD500F0F6FF012804D002287FF4B8 +:1014700014AF2B4B9AE72B4B98E700F0DDFFF3E717 +:1014800094F84630002B7FF408AF94F8483013F0FE +:101490000F01B3D01A06204602D501F0A9FAADE734 +:1014A00001F09CFAAAE794F84630002B7FF4F5AEE1 +:1014B00094F8483013F00F01A0D01B06204602D547 +:1014C00001F082FA9AE701F075FA97E7142284F89E +:1014D000342083F311882B462A4629462046FFF7FD +:1014E0006DFE85F31188E9E65DB1152284F834209C +:1014F00083F311880021D4E90E232046FFF75EFE16 +:10150000FDE60B2284F8342083F311882B462A460B +:1015100029462046FFF764FEE3E700BFE4340008F5 +:10152000DC340008E034000838B590F83430044664 +:10153000002B3ED0063BDAB20F2A34D80F2B32D81C +:10154000DFE803F0373131082232313131313131C6 +:1015500031313737C56BB0F84A309D4214D2C36879 +:101560001B8AB5FBF3F203FB12556DB9302383F3ED +:1015700011882B462A462946FFF732FE85F311884B +:101580000A2384F834300EE0142384F834303023F6 +:1015900083F3118800231A4619462046FFF70EFEF2 +:1015A000002383F3118838BD036C03B198470023EF +:1015B000E7E70021204601F007FA0021204601F06C +:1015C000F9F963681B6813B1062120469847062382 +:1015D000D7E7000010B590F83430142B044629D01A +:1015E00017D8062B05D001D81BB110BD093B022B23 +:1015F000FBD80021204601F0E7F90021204601F048 +:10160000D9F963681B6813B1062120469847062361 +:1016100019E0152BE9D10B2380F83430302383F304 +:10162000118800231A461946FFF7DAFD002383F3D9 +:101630001188DAE7C3689B695B68002BD5D1036C1E +:1016400003B19847002384F83430CEE700230375B4 +:10165000826803691B6899689142FBD25A680360EB +:101660004260106058607047002303758268036908 +:101670001B6899689142FBD85A6803604260106009 +:101680005860704708B50846302383F311880B7DF6 +:10169000032B05D0042B0DD02BB983F3118808BD83 +:1016A0008B6900221A604FF0FF338361FFF7CEFF92 +:1016B0000023F2E7D1E9003213605A60F3E700003B +:1016C000FFF7C4BF054BD9680875186802681A602F +:1016D000536001220275D860FEF714BE98230020E3 +:1016E00030B50C4BDD684B1C87B004460FD02B4641 +:1016F000094A684600F04EF92046FFF7E3FF009BD9 +:1017000013B1684600F050F9A86907B030BDFFF783 +:10171000D9FFF9E79823002085160008044B1A68C2 +:10172000DB6890689B68984294BF00200120704756 +:1017300098230020084B10B51C68D86822681A60EE +:10174000536001222275DC60FFF78EFF01462046C0 +:10175000BDE81040FEF7D6BD9823002038B5074CF1 +:1017600007490848012300252370656001F044FB08 +:101770000223237085F3118838BD00BF00260020A6 +:10178000EC3400089823002000F044B9034A516863 +:1017900053685B1A9842FBD8704700BF001000E006 +:1017A0008B60022308618B82084670478368A3F12F +:1017B000840243F8142C026943F8442C426943F82C +:1017C000402C094A43F8242CC26843F8182C022202 +:1017D00003F80C2C002203F80B2C044A43F8102CBD +:1017E000A3F12000704700BF1D03000898230020CC +:1017F00008B5FFF7DBFFBDE80840FFF761BF000059 +:10180000024BDB6898610F20FFF75CBF9823002034 +:10181000302383F31188FFF7F3BF000008B50146BA +:10182000302383F311880820FFF75AFF002383F346 +:10183000118808BD064BDB6839B1426818605A60F0 +:10184000136043600420FFF74BBF4FF0FF30704739 +:10185000982300200368984206D01A6802605060FE +:1018600099611846FFF72CBF7047000038B5044651 +:101870000D462068844200D138BD036823605C6057 +:101880008561FFF71DFFF4E710B503689C68A2426D +:101890000CD85C688A600B604C6021605960996864 +:1018A0008A1A9A604FF0FF33836010BD1B68121BC9 +:1018B000ECE700000A2938BF0A2170B504460D463E +:1018C0000A26601901F092FA01F07EFA041BA54283 +:1018D00003D8751C2E460446F3E70A2E04D9BDE84A +:1018E0007040012001F0C8BA70BD0000F8B5144B7B +:1018F0000D46D96103F1100141600A2A196982601D +:1019000038BF0A22016048601861A818144601F027 +:101910005FFA0A2701F058FA431BA342064606D392 +:101920007C1C281901F062FA27463546F2E70A2F97 +:1019300004D9BDE8F840012001F09EBAF8BD00BF0F +:1019400098230020F8B506460D4601F03DFA0F4AEF +:10195000134653F8107F9F4206D12A46014630466F +:10196000BDE8F840FFF7C2BFD169BB68441A2C1923 +:1019700028BF2C46A34202D92946FFF79BFF2246E7 +:1019800031460348BDE8F840FFF77EBF98230020AA +:10199000A823002010B4C0E9032300235DF8044B02 +:1019A0004361FFF7CFBF000010B5194C236998427F +:1019B0000DD0D0E90032816813605A609A680A44F9 +:1019C0009A60002303604FF0FF33A36110BD2346EC +:1019D000026843F8102F53600022026022699A4285 +:1019E00003D1BDE8104001F0FBB9936881680B4456 +:1019F000936001F0E9F92269E1699268441AA24210 +:101A0000E4D91144BDE81040091AFFF753BF00BFE5 +:101A1000982300202DE9F047DFF8BC8008F110077B +:101A20002C4ED8F8105001F0CFF9D8F81C40AA6815 +:101A3000031B9A423ED81444D5E900324FF0000906 +:101A4000C8F81C4013605A60C5F80090D8F81030F0 +:101A5000B34201D101F0C4F989F31188D5E903310A +:101A600028469847302383F311886B69002BD8D020 +:101A700001F0AAF96A69A0EB04094A4582460DD231 +:101A8000022001F0F9F90022D8F81030B34208D151 +:101A900051462846BDE8F047FFF728BF121A2244F6 +:101AA000F2E712EB090938BF4A4629463846FFF7E4 +:101AB000EBFEB5E7D8F81030B34208D01444211A31 +:101AC000C8F81C00A960BDE8F047FFF7F3BEBDE809 +:101AD000F08700BFA8230020982300200020704733 +:101AE000FEE70000704700004FF0FF307047000035 +:101AF00002290CD0032904D00129074818BF00206F +:101B00007047032A05D8054800EBC2007047044817 +:101B100070470020704700BFC43500082022002015 +:101B20007835000870B59AB00546084601A91446F4 +:101B300000F0C2F801A8FFF7BFF8431C5B00C5E93D +:101B400000340022237003236370C6B201AB023459 +:101B50001046D1B28E4204F1020401D81AB070BD11 +:101B600013F8011B04F8021C04F8010C0132F0E721 +:101B700008B5302383F311880348FFF759FA00238F +:101B800083F3118808BD00BF0826002090F8443078 +:101B900003F01F02012A07D190F845200B2A03D138 +:101BA0000023C0E90E3315E003F06003202B08D1B9 +:101BB000B0F848302BB990F84520212A03D81F2AC5 +:101BC00004D8FFF717BA222AEBD0FAE7034A826358 +:101BD0000722C26303640120704700BF182200205F +:101BE00007B5052917D8DFE801F0191603191920E0 +:101BF000302383F31188104A01900121FFF7BAFACC +:101C000001980E4A0221FFF7B5FA0D48FFF7DCF9FB +:101C1000002383F3118803B05DF804FB302383F3C2 +:101C200011880748FFF7A6F9F2E7302383F31188FC +:101C30000348FFF7BDF9EBE7183500083C3500080D +:101C40000826002038B50C4D0C4C0D492A4604F1ED +:101C50000800FFF767FF05F1CA0204F11000094907 +:101C6000FFF760FF05F5CA7204F118000649BDE8E8 +:101C70003840FFF757BF00BFD02A002020220020A5 +:101C8000F8340008023500080D35000870B5044628 +:101C900008460D46FFF710F8C6B220460134037817 +:101CA0000BB9184670BD32462946FEF7F1FF0028F1 +:101CB000F3D10120F6E700002DE9F84F05460C4668 +:101CC000FEF7FAFF2B49C6B22846FFF7DFFF08B13F +:101CD0000536F6B228492846FFF7D8FF08B1103676 +:101CE000F6B2632E0DD8DFF88C80DFF88C90234F8E +:101CF000DFF890A0DFF890B02E7846B92670BDE8E6 +:101D0000F88F29462046BDE8F84F01F09BBB252EF1 +:101D10002BD1072241462846FEF7BAFF58B9DBF817 +:101D200000302360DBF804306360DBF80830A36028 +:101D300007350C34E0E7082249462846FEF7A8FF9D +:101D400098B90F4BA21C197809090232C95D02F833 +:101D5000041C13F8011B01F00F015345C95D02F883 +:101D6000031CF0D118340835C6E704F8016B0135BF +:101D7000C2E700BFE43500080D350008F93500085A +:101D8000107AFF1F1C7AFF1FEC350008BFF34F8F3E +:101D9000024AD368DB03FCD4704700BF003C02401A +:101DA00008B5094B1B7873B9FFF7F0FF074B1A69A9 +:101DB000002ABFBF064A5A6002F188325A601A6888 +:101DC00022F480621A6008BD2E2D0020003C0240E3 +:101DD0002301674508B50B4B1B7893B9FFF7D6FF76 +:101DE000094B1A6942F000421A611A6842F48052A3 +:101DF0001A601A6822F480521A601A6842F48062EB +:101E00001A6008BD2E2D0020003C02400B28F0B5C2 +:101E100016D80C4C0C4923787BB90C4D0E460C237C +:101E20004FF0006255F8047B46F8042B013B13F099 +:101E3000FF033A44F6D10123237051F82000F0BD8E +:101E40000020FCE7602D0020302D00200C3600081B +:101E5000014B53F8200070470C3600080C207047E7 +:101E60000B2810B5044601D9002010BDFFF7CEFFA6 +:101E7000064B53F824301844C21A0BB90120F4E77A +:101E800012680132F0D1043BF6E700BF0C360008BF +:101E90000B2810B5044621D8FFF778FFFFF780FF25 +:101EA0000F4AF323D360C300DBB243F4007343F063 +:101EB00002031361136943F480331361FFF766FF74 +:101EC000FFF7A4FF074B53F8241000F0D9F8FFF7F1 +:101ED00081FF2046BDE81040FFF7C2BF002010BDC3 +:101EE000003C02400C360008F8B512F0010314461D +:101EF00042D18218B2F1016F57D82D4B1B6813F0F5 +:101F0000010352D02B4DFFF74BFFF323EB60FFF79C +:101F10003DFF40F20127032C15D824F00104661878 +:101F2000244C401A40F20117B142236900EB01052D +:101F300024D123F001032361FFF74CFF0120F8BDFA +:101F4000043C0430E7E78307E7D12B6923F44073AF +:101F50002B612B693B432B6151F8046B0660BFF387 +:101F60004F8FFFF713FF03689E42E9D02B6923F0E0 +:101F700001032B61FFF72EFF0020E0E723F44073FD +:101F8000236123693B4323610B882B80BFF34F8F71 +:101F9000FFF7FCFE2D8831F8023BADB2AB42C3D057 +:101FA000236923F001032361E4E71846C7E700BF74 +:101FB00000380240003C0240084908B50B7828B1BF +:101FC0001BB9FFF7EDFE01230B7008BD002BFCD001 +:101FD000BDE808400870FFF7FDBE00BF2E2D0020B1 +:101FE00010B50244064BD2B2904200D110BD441C41 +:101FF00000B253F8200041F8040BE0B2F4E700BF50 +:10200000502800400F4B30B51C6F240407D41C6FC0 +:1020100044F400741C671C6F44F400441C670A4CB1 +:10202000236843F4807323600244084BD2B2904289 +:1020300000D130BD441C00B251F8045B43F820507D +:10204000E0B2F4E700380240007000405028004041 +:1020500007B5012201A90020FFF7C2FF019803B0D4 +:102060005DF804FB13B50446FFF7F2FFA04205D06C +:10207000012201A900200194FFF7C4FF02B010BDA6 +:1020800070470000034B1A681AB9034AD2F8742843 +:102090001A607047642D00200030024008B5FFF739 +:1020A000F1FF024B1868C0F3407008BD642D00209A +:1020B00070470000FEE700000A4B0B480B4A9042B5 +:1020C0000BD30B4BDA1C121AC11E22F003028B42F7 +:1020D00038BF00220021FEF7F7BD53F8041B40F87B +:1020E000041BECE7B8370008602E0020602E0020AB +:1020F000602E002070B5D0E915439E6800224FF095 +:10210000FF3504EB42135101D3F800090028BEBF8C +:10211000D3F8000940F08040C3F80009D3F8000B61 +:102120000028BEBFD3F8000B40F08040C3F8000B7E +:10213000013263189642C3F80859C3F8085BE0D22D +:102140004FF00113C4F81C3870BD0000890141F044 +:102150002001016103699B06FCD41220FFF716BB26 +:1021600010B5054C2046FEF7E5FF4FF0A043636530 +:10217000024BA36510BD00BF682D0020603600082B +:1021800070B50378012B054650D12A4B446D984217 +:102190001BD1294B5A6B42F080025A635A6D42F0B0 +:1021A00080025A655A6D5A6942F080025A615A6932 +:1021B00022F080025A610E2143205B6900F022FC6C +:1021C0001E4BE3601E4BC4F800380023C4F8003EE9 +:1021D000C02323606E6D4FF40413A3633369002B97 +:1021E000FCDA012333610C20FFF7D0FA3369DB07F7 +:1021F000FCD41220FFF7CAFA3369002BFCDA002660 +:10220000A6602846FFF776FF6B68C4F81068DB68A5 +:10221000C4F81468C4F81C684BB90A4BA3614FF0AA +:10222000FF336361A36843F00103A36070BD064BF5 +:10223000F4E700BF682D0020003802404014004041 +:1022400003002002003C30C0083C30C0F8B5446DAB +:10225000054600212046FFF779FFA96D00234FF0C6 +:1022600001128F68C4F834384FF00066C4F81C2897 +:102270004FF0FF3004EB431201339F42C2F8006974 +:10228000C2F8006BC2F80809C2F8080BF2D20B685A +:102290006A6DEB65636210231361166916F0100610 +:1022A000FBD11220FFF772FAD4F8003823F4FE6352 +:1022B000C4F80038A36943F4402343F01003A3613A +:1022C0000923C4F81038C4F814380A4BEB604FF0F7 +:1022D000C043C4F8103B084BC4F8003BC4F8106975 +:1022E000C4F80039EB6D03F1100243F48013EA6582 +:1022F000A362F8BD3C36000840800010426D90F8A3 +:102300004E10D2F8003823F4FE6343EA0113C2F8FA +:10231000003870472DE9F84300EB8103456DDA681A +:10232000166806F00306731E022B05EB41130C46DC +:1023300080460FFA81F94FEA41104FF00001C3F8CF +:10234000101B4FF0010104F1100398BFB60401FA0D +:1023500003F391698EBF334E06F1805606F50046B1 +:1023600000293AD0578A04F15801490137436F5088 +:10237000D5F81C180B43C5F81C382B180021C3F8DE +:10238000101953690127611EA7409BB3138A928BD2 +:102390009B08012A88BF5343D8F85C20981842EA6A +:1023A000034301F1400205EB8202C8F85C002146BC +:1023B00053602846FFF7CAFE08EB8900C3681B8AF2 +:1023C00043EA8453483464011E432E51D5F81C3827 +:1023D0001F43C5F81C78BDE8F88305EB4917D7F80B +:1023E000001B21F40041C7F8001BD5F81C1821EA96 +:1023F0000303C0E704F13F0305EB83030A4A5A6075 +:1024000028462146FFF7A2FE05EB4910D0F8003917 +:1024100023F40043C0F80039D5F81C3823EA070735 +:10242000D7E700BF0080001000040002826D126830 +:10243000C265FFF75FBE00005831436D49015B582C +:1024400013F4004004D013F4001F0CBF022001203D +:10245000704700004831436D49015B5813F4004058 +:1024600004D013F4001F0CBF0220012070470000AD +:1024700000EB8101CB68196A0B6813604B685360ED +:102480007047000000EB810330B5DD68AA6913686E +:10249000D36019B9402B84BF402313606B8A146842 +:1024A000426D1C44013CB4FBF3F46343033323F05B +:1024B000030302EB411043EAC44343F0C043C0F8B6 +:1024C000103B2B6803F00303012B09B20ED1D2F8A5 +:1024D000083802EB411013F4807FD0F8003B14BFA2 +:1024E00043F0805343F00053C0F8003B02EB41122D +:1024F000D2F8003B43F00443C2F8003B30BD00007B +:102500002DE9F041244D6E6D06EB40130446D3F8DF +:10251000087BC3F8087B38070AD5D6F814381907A2 +:1025200006D505EB84032146DB6828465B6898479F +:10253000FA071FD5D6F81438DB071BD505EB840343 +:10254000D968CCB98B69488A5A68B2FBF0F600FBAF +:1025500016228AB91868DA6890420DD2121AC3E9B5 +:102560000024302383F311880B482146FFF78AFFAC +:1025700084F31188BDE8F081012303FA04F26B892A +:1025800023EA02036B81CB68002BF3D0214602487B +:10259000BDE8F041184700BF682D002000EB810323 +:1025A00070B5DD68436D6C692668E6604A0156BB0C +:1025B0001A444FF40020C2F810092A6802F00302FE +:1025C000012A0AB20ED1D3F8080803EB421410F422 +:1025D000807FD4F8000914BF40F0805040F00050D4 +:1025E000C4F8000903EB4212D2F8000940F004409D +:1025F000C2F80009D3F83408012202FA01F10143BC +:10260000C3F8341870BD19B9402E84BF4020206033 +:1026100020682E8A8419013CB4FBF6F440EAC440D9 +:1026200040F000501A44C6E72DE9F8433B4D6E6D6B +:1026300006EB40130446D3F80889C3F8088918F05C +:10264000010F4FEA40171AD0D6F81038DB0716D51D +:1026500005EB8003D9684B691868DA68904230D27C +:10266000121A4FF000091A60C3F80490302383F364 +:10267000118821462846FFF791FF89F3118818F049 +:10268000800F1CD0D6F834380126A640334216D02D +:1026900005EB84036D6DD3F80CC0DCF81420013415 +:1026A000E4B2D2F800E005EB04342F4451687145E0 +:1026B00015D3D5F8343823EA0606C5F83468BDE8E2 +:1026C000F883012303FA04F22B8923EA02032B8106 +:1026D0008B68002BD3D0214628469847CFE7BCF81B +:1026E0001000AEEB0103834228BF0346D7F8180958 +:1026F00080B2B3EB800FE2D89068A0F1040959F8DA +:10270000048FC4F80080A0EB09089844B8F1040FC6 +:10271000F5D818440B4490605360C7E7682D00203B +:102720002DE9F74FA24C656D6E69AB691E4016F43A +:1027300080586E6107D02046FEF764FD03B0BDE807 +:10274000F04F00F047BC002E12DAD5F8003E984852 +:102750009B071EBFD5F8003E23F00303C5F8003EDB +:10276000D5F8043823F00103C5F80438FEF774FDEA +:10277000370505D58E48FFF7BDFC8D48FEF75AFD9D +:10278000B0040CD5D5F8083813F0060FEB6823F425 +:1027900070530CBF43F4105343F4A053EB60310764 +:1027A0001BD56368DB681BB9AB6923F00803AB6119 +:1027B0002378052B0CD1D5F8003E7D489A071EBF23 +:1027C000D5F8003E23F00303C5F8003EFEF744FDB4 +:1027D0006368DB680BB176489847F30274D4B7029C +:1027E00027D5D4F85490DFF8C8B100274FF0010A7C +:1027F00009EB4712D2F8003B03F44023B3F5802FD6 +:1028000011D1D2F8003B002B0DDA62890AFA07F3E6 +:1028100022EA0303638104EB8703DB68DB6813B1FF +:10282000394658469847A36D01379B68FFB29F42CF +:10283000DED9F00617D5676D3A6AC2F30A1002F0C6 +:102840000F0302F4F012B2F5802F00F08580B2F58C +:10285000402F08D104EB83030022DB681B6A07F5D5 +:10286000805790426AD13003D5F8184813D5E10358 +:1028700002D50020FFF744FEA20302D50120FFF796 +:102880003FFE630302D50220FFF73AFE270302D57D +:102890000320FFF735FE75037FF550AFE00702D543 +:1028A0000020FFF7C1FEA10702D50120FFF7BCFE03 +:1028B000620702D50220FFF7B7FE23077FF53EAF80 +:1028C0000320FFF7B1FE39E7636DDFF8E4A0019361 +:1028D00000274FF00109A36D9B685FFA87FB9B45BA +:1028E0003FF67DAF019B03EB4B13D3F8001901F4C6 +:1028F0004021B1F5802F1FD1D3F8001900291BDA30 +:10290000D3F8001941F09041C3F80019D3F8001929 +:102910000029FBDB5946606DFFF718FC218909FA95 +:102920000BF321EA0303238104EB8B03DB689B6831 +:1029300013B15946504698470137CCE7910708BF75 +:10294000D7F80080072A98BF03F8018B02F1010233 +:1029500098BF4FEA182884E7023304EB830207F597 +:1029600080575268D2F818C0DCF80820DCE9001C57 +:10297000A1EB0C0C002188420AD104EB83046368AC +:102980009B699A6802449A605A6802445A606AE7EE +:1029900011F0030F08BFD7F800808C4588BF02F8FC +:1029A000018B01F1010188BF4FEA1828E3E700BF5E +:1029B000682D0020436D03EB4111D1F8003B43F437 +:1029C0000013C1F8003B7047436D03EB4111D1F890 +:1029D000003943F40013C1F800397047436D03EB2D +:1029E0004111D1F8003B23F40013C1F8003B7047BC +:1029F000436D03EB4111D1F8003923F40013C1F802 +:102A00000039704700F1604303F561430901C9B221 +:102A100083F80013012200F01F039A4043099B0032 +:102A200003F1604303F56143C3F880211A607047E6 +:102A300030B5039C0172043304FB0325C0E906533F +:102A4000049B03630021059BC160C0E90000C0E94D +:102A50000422C0E90842C0E90A11436330BD000006 +:102A6000416A0022C0E90411C0E90A22C2606FF085 +:102A70000101FEF7FBBE0000D0E90432934201D110 +:102A8000C2680AB9181D70470020704703691960B1 +:102A9000C2680132C260C269134482690361934211 +:102AA00024BF436A03610021FEF7D4BE38B5044653 +:102AB0000D46E3683BB16269131D1268A3621344BB +:102AC000E362002007E0237A33B929462046FEF767 +:102AD000B1FE0028EDDA38BD6FF00100FBE7000021 +:102AE000C368C269013BC36043691344826943619F +:102AF000934224BF436A436100238362036B03B1A3 +:102B00001847704770B53023044683F31188866AEE +:102B10003EB9FFF7CBFF054618B186F3118828466A +:102B200070BDA36AE26A13F8015BA362934202D309 +:102B30002046FFF7D5FF002383F31188EFE700005D +:102B40002DE9F84F04460E46174698464FF03009D7 +:102B500089F311880025AA46D4F828B0BBF1000FEC +:102B600009D141462046FFF7A1FF20B18BF3118820 +:102B70002846BDE8F88FD4E90A12A7EB050B521AD4 +:102B8000934528BF9346BBF1400F1BD9334601F153 +:102B9000400251F8040B43F8040B9142F9D1A36AA7 +:102BA00040334036A3624035D4E90A239A4202D327 +:102BB0002046FFF795FF8AF31188BD42D8D289F3EA +:102BC0001188C9E730465A46FEF758F8A36A5B44B5 +:102BD0005E44A3625D44E7E710B5029C01720433D2 +:102BE00003FB0421C0E906130023C0E90A33039B59 +:102BF0000363049BC460C0E90000C0E90422C0E98B +:102C00000842436310BD0000026AC260426AC0E924 +:102C100004220022C0E90A226FF00101FEF726BE5D +:102C2000D0E904239A4201D1C26822B9184650F86B +:102C3000043B0B60704700231846FAE7C368C2697B +:102C40000133C3604369134482694361934224BFE3 +:102C5000436A43610021FEF7FDBD000038B504461C +:102C60000D46E3683BB123691A1DA262E269134471 +:102C7000E362002007E0237A33B929462046FEF7B5 +:102C8000D9FD0028EDDA38BD6FF00100FBE7000048 +:102C900003691960C268013AC260C269134482695B +:102CA0000361934224BF436A036100238362036B81 +:102CB00003B118477047000070B530230D46044635 +:102CC000114683F31188866A2EB9FFF7C7FF10B14A +:102CD00086F3118870BDA36A1D70A36AE26A01338E +:102CE0009342A36204D3E16920460439FFF7D0FF81 +:102CF000002080F31188EDE72DE9F84F04460D46DA +:102D0000904699464FF0300A8AF311880026B34660 +:102D1000A76A4FB949462046FFF7A0FF20B187F3C5 +:102D200011883046BDE8F88FD4E90A073A1AA8EBB3 +:102D30000607974228BF1746402F1BD905F14003CD +:102D400055F8042B40F8042B9D42F9D1A36A403377 +:102D5000A3624036D4E90A239A4204D3E1692046AB +:102D60000439FFF795FF8BF311884645D9D28AF3D2 +:102D70001188CDE729463A46FDF780FFA36A3B4418 +:102D80003D44A3623E44E5E7D0E904239A4217D1CB +:102D9000C3689BB1836A8BB1043B9B1A0ED013604E +:102DA000C368013BC360C3691A44836902619A42E4 +:102DB00024BF436A036100238362012318467047DE +:102DC0000023FBE700F030B94FF08043586A7047AA +:102DD0004FF08043002258631A610222DA60704784 +:102DE0004FF080430022DA60704700004FF08043CC +:102DF00058637047FEE7000070B51B4B0163002568 +:102E0000044686B0586085620E4600F0BFF804F1B3 +:102E10001003C4E904334FF0FF33C4E90635C4E9B5 +:102E20000044A560E562FFF7CFFF2B460246C4E9E8 +:102E3000082304F134010D4A256580232046FEF75E +:102E4000AFFC0123E0600A4A0375009272680192A8 +:102E5000B268CDE90223074B6846CDE90435FEF799 +:102E6000C7FC06B070BD00BF002600206C3600080D +:102E700071360008F52D0008024AD36A1843D06263 +:102E8000704700BF982300204B6843608B688360C5 +:102E9000CB68C3600B6943614B6903628B69436212 +:102EA0000B6803607047000008B5264B26481A6976 +:102EB00040F2FF110A431A611A6922F4FF7222F0EC +:102EC00001021A611A691A6B0A431A631A6D0A43DE +:102ED0001A651E4A1B6D1146FFF7D6FF02F11C0151 +:102EE00000F58060FFF7D0FF02F1380100F5806047 +:102EF000FFF7CAFF02F1540100F58060FFF7C4FF3D +:102F000002F1700100F58060FFF7BEFF02F18C0155 +:102F100000F58060FFF7B8FF02F1A80100F58060BE +:102F2000FFF7B2FF02F1C40100F58060FFF7ACFFCC +:102F300002F1E00100F58060FFF7A6FFBDE8084060 +:102F400000F0EEB800380240000002407836000879 +:102F500008B500F059FAFEF701FCFFF793F8BDE859 +:102F60000840FEF76FBE000070470000EFF30983D2 +:102F700005494A6B22F001024A63683383F30988EA +:102F8000002383F31188704700EF00E0302080F3C6 +:102F9000118862B60C4B0D4AD96821F4E06109042E +:102FA000090C0A43DA60D3F8FC20094942F0807228 +:102FB000C3F8FC200A6842F001020A602022DA7796 +:102FC00083F82200704700BF00ED00E00003FA051F +:102FD000001000E010B5302383F311880E4B5B68BE +:102FE00013F4006314D0F1EE103AEFF30984683C57 +:102FF0004FF08073E361094BDB6B236684F3098830 +:10300000FEF78CFB10B1064BA36110BD054BFBE72F +:1030100083F31188F9E700BF00ED00E000EF00E066 +:103020002F030008320300080F4B1A6C42F0010214 +:103030001A641A6E42F001021A660C4A1B6E9368FB +:1030400043F0010393604FF0804353229A624FF0A4 +:10305000FF32DA6200229A615A63DA605A60012212 +:103060005A611A60704700BF00380240002004E037 +:103070004FF0804208B51169D3680B40D9B2C943FB +:103080009B07116107D5302383F31188FEF77CFB82 +:10309000002383F3118808BD1F4B1A696FEAC252DF +:1030A0006FEAD2521A611A69C2F308021A614FF02C +:1030B000FF301A695A69586100215A6959615A6981 +:1030C0001A6A62F080521A621A6A02F080521A6218 +:1030D0001A6A5A6A58625A6A59625A6A1A6C42F0F3 +:1030E00080521A641A6E42F080521A661A6E0B4AA7 +:1030F000106840F480701060186F00F44070B0F5F4 +:10310000007F1EBF4FF4803018671967536823F49F +:103110000073536000F054B9003802400070004062 +:10312000334B4FF080521A64324A4FF440411160E1 +:103130001A6842F001021A601A689107FCD59A6871 +:1031400022F003029A602A4B9A6812F00C02FBD11B +:10315000196801F0F90119609A601A6842F4803226 +:103160001A601A689203FCD55A6F42F001025A673E +:103170001F4B5A6F9007FCD51F4A5A601A6842F0DD +:1031800080721A601B4A53685904FCD5184B1A68A0 +:103190009201FCD5194A9A60194B1A68194B9A4248 +:1031A000194B21D1194A1168194A91421CD140F298 +:1031B00005121A60144A136803F00F03052BFAD1A5 +:1031C0000B4B9A6842F002029A609A6802F00C0275 +:1031D000082AFAD15A6C42F480425A645A6E42F478 +:1031E00080425A665B6E704740F20572E1E700BFAD +:1031F00000380240007000400854400700948838AE +:10320000002004E011640020003C024000ED00E0DA +:1032100041C20F41074A08B5536903F001035361E6 +:1032200023B1054A13680BB150689847BDE80840C0 +:10323000FFF7D0BE003C0140E02D0020074A08B552 +:10324000536903F00203536123B1054A93680BB13C +:10325000D0689847BDE80840FFF7BCBE003C01407D +:10326000E02D0020074A08B5536903F004035361B9 +:1032700023B1054A13690BB150699847BDE808406E +:10328000FFF7A8BE003C0140E02D0020074A08B52A +:10329000536903F00803536123B1054A93690BB1E5 +:1032A000D0699847BDE80840FFF794BE003C014054 +:1032B000E02D0020074A08B5536903F0100353615D +:1032C00023B1054A136A0BB1506A9847BDE808401C +:1032D000FFF780BE003C0140E02D0020164B10B5EA +:1032E0005C6904F478725A61A30604D5134A936AA0 +:1032F0000BB1D06A9847600604D5104A136B0BB126 +:10330000506B9847210604D50C4A936B0BB1D06BD8 +:103310009847E20504D5094A136C0BB1506C9847E5 +:10332000A30504D5054A936C0BB1D06C9847BDE852 +:103330001040FFF74FBE00BF003C0140E02D0020D1 +:10334000194B10B55C6904F47C425A61620504D5DE +:10335000164A136D0BB1506D9847230504D5134AD7 +:10336000936D0BB1D06D9847E00404D50F4A136EEE +:103370000BB1506E9847A10404D50C4A936E0BB163 +:10338000D06E9847620404D5084A136F0BB1506F92 +:103390009847230404D5054A936F0BB1D06F984723 +:1033A000BDE81040FFF716BE003C0140E02D0020B4 +:1033B00008B5FFF75DFEBDE80840FFF70BBE000053 +:1033C000062108B50846FFF71DFB06210720FFF779 +:1033D00019FB06210820FFF715FB06210920FFF73E +:1033E00011FB06210A20FFF70DFB06211720FFF72E +:1033F00009FB06212820FFF705FBBDE8084007214F +:103400001C20FFF7FFBA000008B5FFF745FE00F0EB +:103410000BF8FDF78DFEFDF765FDFFF7A5FDBDE897 +:103420000840FFF7CFBC00000023054A19460133CE +:10343000102BC2E9001102F10802F8D1704700BF59 +:10344000E02D0020034611F8012B03F8012B002A80 +:10345000F9D1704753544D3332463F3F3F005354E8 +:103460004D3332463430780053544D333246343283 +:10347000780053544D3332463434365858000000E7 +:10348000012033000010410001105A0003105900C0 +:10349000071031000000000054340008130400003D +:1034A0005E3400081904000068340008210400009C +:1034B0007234000800000000610E00084D0E000884 +:1034C000890E0008750E0008810E00086D0E0008B8 +:1034D000590E0008450E0008950E00080000000077 +:1034E000010000000000000063300000E834000824 +:1034F000F0230020002600204172647550696C6F33 +:10350000740025424F415244252D424C002553451D +:103510005249414C2500000002000000000000005C +:103520007D100008E910000840004000A02A00209B +:10353000B02A00200200000000000000030000008C +:10354000000000002D110008000000001000000025 +:10355000C02A002000000000010000000000000060 +:10356000682D002001010200E11B0008F11A00088B +:103570008D1B0008711B0008430000008035000807 +:1035800009024300020100C03209040000010202E6 +:103590000100052400100105240100010424020299 +:1035A0000524060001070582030800FF0904010045 +:1035B000020A000000070501024000000705810221 +:1035C0004000000012000000CC350008120110017C +:1035D00002000040091241570002010203010000ED +:1035E0000403090425424F4152442500466F786583 +:1035F0006572463430357632003031323334353608 +:10360000373839414243444546000000004000003D +:1036100000400000004000000040000000000100E9 +:103620000000020000000200000002000000020092 +:103630000000020000000200000002000000000084 +:103640007112000829150008D51500084000400037 +:10365000C82D0020C82D002001000000D82D00201A +:103660008000000040010000030000006D61696EF1 +:103670000069646C65000000000180060000000025 +:10368000AAAAAAAA00010000FFDF000000000000B3 +:1036900000A00A000000000100000000AAAAAAAAD7 +:1036A00000000001FFFF000000000000000000001B +:1036B0000000001000000000AAAAAAAA0000001042 +:1036C000FFFF0000000000000000000000000000FC +:1036D00000000000AAAAAAAA00000000FFFF000044 +:1036E00000000000000000000000000000000000DA +:1036F000AAAAAAAA00000000FFFF00000000000024 +:10370000000000000000000000000000AAAAAAAA11 +:1037100000000000FFFF00000000000000000000AB +:103720000000000000000000AAAAAAAA00000000F1 +:10373000FFFF00000000000000000000000000008B +:10374000000000000A00000000000000030000006C +:103750000000000000000000000000000000000069 +:103760000000000000000000000000000000000059 +:1037700000000000000000008504000000000000C0 +:1037800000400F0000000000FF009600000000084D +:10379000009600000000080004000000E03500086A +:1037A0000000000000000000000000000000000019 +:0837B000000000000000000011 +:00000001FF diff --git a/Tools/bootloaders/SDMODELH7V2_bl.bin b/Tools/bootloaders/SDMODELH7V2_bl.bin new file mode 100644 index 0000000000000..7746ebe826e78 Binary files /dev/null and b/Tools/bootloaders/SDMODELH7V2_bl.bin differ diff --git a/Tools/bootloaders/SDMODELH7V2_bl.hex b/Tools/bootloaders/SDMODELH7V2_bl.hex new file mode 100644 index 0000000000000..f74bb98df819f --- /dev/null +++ b/Tools/bootloaders/SDMODELH7V2_bl.hex @@ -0,0 +1,1104 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200088528000854 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008F13D00081D3E00082D +:10006000493E0008753E0008A13E000885100008C2 +:10007000AD100008D9100008051100083111000862 +:100080005911000885110008E3020008E302000886 +:10009000E3020008E3020008E3020008CD3E000886 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000313F0008E3020008E3020008E3020008D1 +:1000F000E3020008E3020008E3020008B11100086F +:10010000E3020008E3020008A53F0008E30200083C +:10011000E3020008E3020008E3020008E30200082B +:10012000DD11000805120008311200085D120008F8 +:1001300089120008E3020008E3020008E302000855 +:10014000E3020008E3020008E3020008E3020008FB +:10015000B1120008DD12000809130008E3020008CC +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000871340008E3020008E30200080B +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E30200085D340008E3020008E3020008BF +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F0FCFA78 +:1003500003F00AFB4FF055301F491B4A91423CBF46 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F014FB03F068FBE2 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F0FCBA00060020002200206E +:1003D0000000000808ED00E00000002000060020FA +:1003E00080440008002200205C22002060220020BF +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0AEFDFEE701F04C +:100430003DFD00DFFEE7000038B500F02FFC00F0C6 +:10044000B5FD02F0DFF9054602F012FA0446C0B924 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0D6F90CB100F06A +:1004700075F800F06FFD284600F01EF900F06EF8E8 +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F02BFE0023154A4FF4C7 +:1004D0007A71134801F01AFE002383F31188124C3D +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F092FC322363602B78032B07D16368E1 +:100510002BB9022000F088FC4FF47A73636038BD79 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F067BC022000F05CBC024B0022DD +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0AAFB0220FFF7CBFF454B0021D3F868 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0EDFBB14AAE +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F01BFD0023AB4A4FF4E6 +:1006F0007A71A94801F00AFD002383F31188009B59 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F075FB24B19C4B1B6856 +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F05DFB039B213B1F2B04 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F04BFA0421059005A800F00EFAF8 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F062FB26B10BF033 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F01AFA0220FFF73BFE1FFA86F84046C6 +:1008C00000F022FA0446B0B1039940460136A1F186 +:1008D00040025142514100F027FA0028EDD1BA46BA +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0F0F9013040F06F +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F03CFA019AFF217F4800F05DFA4FEADF +:1009F000A803C8F387027C492846019300F05CFAFB +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0A2F90C +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F001FB8046E7E7384600F046F92E +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F05DF90590E6E70023642104A8BE +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F04BF9EAE70B +:100AC0000220FFF7E5FC00283FF48CAE00F05AF955 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F055F907460421049004A800F0F2 +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0DAF80421059005A800F095 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F007F9002844D00A9B01330BD0BE +:100B600008220AA9002000F0A7F900283AD0202284 +:100B7000FF210AA800F098F9FFF792FC1C4801F049 +:100B800009FA13B0BDE8F08F002E3FF42BAE0BF046 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F0E7F9059800F0EEF946463C461A +:100BD00000F0B6F9A6E506464EE64FF0000901E63C +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0B2F981 +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B5104C50 +:100CA0000025104E01F096FC208030682388834296 +:100CB0000CD800252088013801F088FC23880544E1 +:100CC000013BB5F5802F2380F4D370BD01F07EFC8D +:100CD000336805440133B5F5003F3360E5D3E8E7F9 +:100CE000B62300208823002001F042BD00F10060FF +:100CF00000F500300068704700F10060920000F5D8 +:100D0000003001F0C3BC0000054B1A68054B1B887E +:100D10009B1A834202D9104401F058BC002070474E +:100D200088230020B623002038B50446074D29B19A +:100D300028682044BDE8384001F060BC28682044A1 +:100D400001F04AFC0028F3D038BD00BF8823002002 +:100D50000020704700F1FF5000F58F10D0F8000818 +:100D600070470000064991F8243033B1002308226F +:100D7000086A81F82430FFF7BFBF0120704700BF29 +:100D80008C230020014B1868704700BF0010005CE6 +:100D9000194B01380322084470B51D68174BC5F381 +:100DA0000B042D0C1E88A6420BD15C680A46013C40 +:100DB000824213460FD214F9016F4EB102F8016B53 +:100DC000F6E7013A03F10803ECD181420B4602D267 +:100DD0002C2203F8012B0424094A1688AE4204D1C0 +:100DE000984284BF967803F8016B013C02F104023B +:100DF000F3D1581A70BD00BF0010005C142200200F +:100E00009C400008022802D1014B04229A617047DD +:100E100000080258022803D1024B4FF480229A6145 +:100E2000704700BF00080258022804D1024A5369E3 +:100E300083F00403536170470008025870B50446FC +:100E40004FF47A764CB1412C254628BF412506FB4C +:100E500005F0641B01F09EF8F4E770BD002310B5A7 +:100E6000934203D0CC5CC4540133F9E710BD0000B9 +:100E7000013810B510F9013F3BB191F900409C4297 +:100E800003D11AB10131013AF4E71AB191F9002006 +:100E9000981A10BD1046FCE703460246D01A12F914 +:100EA000011B0029FAD1704702440346934202D045 +:100EB00003F8011BFAE770472DE9F8431F4D14466C +:100EC0000746884695F8242052BBDFF870909CB303 +:100ED00095F824302BB92022FF2148462F62FFF7D6 +:100EE000E3FF95F824004146C0F1080205EB8000BD +:100EF000A24228BF2246D6B29200FFF7AFFF95F874 +:100F00002430A41B17441E449044E4B2F6B2082EC9 +:100F100085F82460DBD1FFF725FF0028D7D108E052 +:100F20002B6A03EB82038342CFD0FFF71BFF00281D +:100F3000CBD10020BDE8F8830120FBE78C23002003 +:100F4000024B1A78024B1A70704700BFB42300207E +:100F50001022002010B5114C114800F06FFB214603 +:100F60000F4800F097FB24684FF47A70D4F8902073 +:100F7000D2F8043843F00203C2F80438FFF75EFFEA +:100F80000849204600F094FCD4F89020D2F80438A8 +:100F900023F00203C2F8043810BD00BF5842000815 +:100FA000B02600206042000870470000F0B5A1B0F4 +:100FB00071B600230120002480261A46194600F04D +:100FC0004BFA4FF4D067214A3D25136923BBD2F871 +:100FD00010310BBB036804F1006199600368C3F82A +:100FE0000CD003685E6003681F6001680B6843F003 +:100FF00001030B6001680B6823F01E030B6001689E +:101000000B68DB07FCD4037B8034416805FA03F3EB +:10101000B4F5001F0B60D8D100F05EFAB4F5001FE4 +:1010200011D000240A4E0B4D012001F0A1FB3388A2 +:10103000A34205D928682044013401F0DFFAF6E71D +:10104000002001F095FB61B621B0F0BD00200052F8 +:10105000B62300208823002030B50A44084D914271 +:101060000DD011F8013B5840082340F30004013B28 +:101070002C4013F0FF0384EA5000F6D1EFE730BDB7 +:101080002083B8ED08B5074B074A196801F03D0108 +:10109000996053680BB190689847BDE8084001F02B +:1010A00029BC00BF00000240B823002008B5084B4F +:1010B0001968890901F03D018A019A60054AD368DF +:1010C0000BB110699847BDE8084001F013BC00BFA0 +:1010D00000000240B823002008B5084B1968090C2D +:1010E00001F03D010A049A60054A53690BB1906909 +:1010F0009847BDE8084001F0FDBB00BF000002407A +:10110000B823002008B5084B1968890D01F03D018E +:101110008A059A60054AD3690BB1106A9847BDE801 +:10112000084001F0E7BB00BF00000240B8230020E8 +:1011300008B5074B074A596801F03D01D960536A69 +:101140000BB1906A9847BDE8084001F0D3BB00BFDF +:1011500000000240B823002008B5084B59688909EF +:1011600001F03D018A01DA60054AD36A0BB1106BC8 +:101170009847BDE8084001F0BDBB00BF0000024039 +:10118000B823002008B5084B5968090C01F03D014F +:101190000A04DA60054A536B0BB1906B9847BDE8BF +:1011A000084001F0A7BB00BF00000240B8230020A8 +:1011B00008B5084B5968890D01F03D018A05DA60D0 +:1011C000054AD36B0BB1106C9847BDE8084001F09D +:1011D00091BB00BF00000240B823002008B5074BB8 +:1011E000074A196801F03D019960536C0BB1906C8E +:1011F0009847BDE8084001F07DBB00BF00040240F5 +:10120000B823002008B5084B1968890901F03D0191 +:101210008A019A60054AD36C0BB1106D9847BDE8FE +:10122000084001F067BB00BF00040240B823002063 +:1012300008B5084B1968090C01F03D010A049A60D1 +:10124000054A536D0BB1906D9847BDE8084001F019 +:1012500051BB00BF00040240B823002008B5084B72 +:101260001968890D01F03D018A059A60054AD36D20 +:101270000BB1106E9847BDE8084001F03BBB00BFC2 +:1012800000040240B823002008B5074B074A5968FC +:1012900001F03D01D960536E0BB1906E9847BDE8E7 +:1012A000084001F027BB00BF00040240B823002023 +:1012B00008B5084B5968890901F03D018A01DA60D7 +:1012C000054AD36E0BB1106F9847BDE8084001F096 +:1012D00011BB00BF00040240B823002008B5084B32 +:1012E0005968090C01F03D010A04DA60054A536FA0 +:1012F0000BB1906F9847BDE8084001F0FBBA00BF02 +:1013000000040240B823002008B5084B5968890D35 +:1013100001F03D018A05DA60054AD36F13B1D2F8B6 +:1013200080009847BDE8084001F0E4BA000402409C +:10133000B823002000230C4910B51A460B4C0B6053 +:1013400054F82300026001EB430004334260402B59 +:10135000F6D1074A4FF0FF339360D360C2F80834E8 +:10136000C2F80C3410BD00BFB8230020AC40000808 +:10137000000002400F28F8B510D9102810D011280D +:1013800011D0122808D10F240720DFF8C8E0012669 +:10139000DEF80050A04208D9002653E00446F4E7E6 +:1013A0000F240020F1E70724FBE706FA00F73D428F +:1013B0004AD1264C4FEA001C3D4304EB00160EEBCD +:1013C000C000CEF80050C0E90123FBB273B1204841 +:1013D000D0F8D83043F00103C0F8D830D0F800314D +:1013E00043F00103C0F80031D0F8003117F47F4F0B +:1013F0000ED01748D0F8D83043F00203C0F8D830E8 +:10140000D0F8003143F00203C0F80031D0F80031C9 +:1014100054F80C00036823F01F030360056815F0FF +:101420000105FBD104EB0C033D2493F80CC05F686D +:1014300004FA0CF43C6021240560446112B1987BED +:1014400000F054F83046F8BD0130A3E7AC40000886 +:1014500000440258B823002010B5302484F31188CA +:10146000FFF788FF002383F3118810BD10B50446F1 +:10147000807B00F051F801231549627B03FA02F2E8 +:101480000B6823EA0203DAB20B6072B9114AD2F890 +:10149000D81021F00101C2F8D810D2F8001121F0C3 +:1014A0000101C2F80011D2F8002113F47F4F0ED1D0 +:1014B000084BD3F8D82022F00202C3F8D820D3F882 +:1014C000002122F00202C3F80021D3F8003110BD40 +:1014D000B82300200044025808B5302383F3118854 +:1014E000FFF7C4FF002383F3118808BD090100F151 +:1014F0006043012203F56143C9B283F8001300F091 +:101500001F039A4043099B0003F1604303F56143C5 +:10151000C3F880211A60704700F01F0301229A402F +:10152000430900F160409B0000F5614003F1604316 +:1015300003F56143C3F88020C3F88021002380F8BD +:1015400000337047026843681143016003B11847D4 +:101550007047000013B5406B00F58054D4F8A438F0 +:101560001A681178042914D1017C022911D1197942 +:10157000012312898B4013420BD101A94C3002F098 +:10158000A9F8D4F8A4480246019B2179206800F00C +:10159000DFF902B010BD0000143002F02BB80000DB +:1015A0004FF0FF33143002F025B800004C3002F049 +:1015B000FDB800004FF0FF334C3002F0F7B80000E8 +:1015C000143001F0F9BF00004FF0FF31143001F08A +:1015D000F3BF00004C3002F0C9B800004FF0FF32FA +:1015E0004C3002F0C3B800000020704710B500F581 +:1015F0008054D4F8A4381A681178042917D1017CD2 +:10160000022914D15979012352898B4013420ED1FA +:10161000143001F08BFF024648B1D4F8A4484FF4CF +:10162000407361792068BDE8104000F07FB910BDBB +:10163000406BFFF7DBBF0000704700007FB5124B27 +:1016400001250426044603600023057400F184028A +:1016500043602946C0E902330C4B029014300193D9 +:101660004FF44073009601F03DFF094B04F694429D +:10167000294604F14C000294CDE900634FF4407315 +:1016800002F004F804B070BDAC4100083116000847 +:10169000551500080A68302383F311880B790B3342 +:1016A00042F823004B79133342F823008B7913B1AE +:1016B0000B3342F8230000F58053C3F8A41802232B +:1016C0000374002080F311887047000038B5037F51 +:1016D000044613B190F85430ABB90125201D022106 +:1016E000FFF730FF04F114006FF00101257700F0DF +:1016F00079FC04F14C0084F854506FF00101BDE80E +:10170000384000F06FBC38BD10B5012104460430EC +:10171000FFF718FF0023237784F8543010BD000032 +:1017200038B504460025143001F0F4FE04F14C00F5 +:10173000257701F0C3FF201D84F854500121FFF7E5 +:1017400001FF2046BDE83840FFF750BF90F88030D9 +:1017500003F06003202B06D190F881200023212A7A +:1017600003D81F2A06D800207047222AFBD1C0E9DF +:101770001D3303E0034A426707228267C3670120E3 +:10178000704700BF2C22002037B500F58055D5F8F2 +:10179000A4381A68117804291AD1017C022917D1BA +:1017A0001979012312898B40134211D100F14C04A5 +:1017B000204602F043F858B101A9204601F08AFF03 +:1017C000D5F8A4480246019B2179206800F0C0F8B2 +:1017D00003B030BD01F10B03F0B550F8236085B0C4 +:1017E00004460D46FEB1302383F3118804EB8507D0 +:1017F000301D0821FFF7A6FEFB6806F14C005B696F +:101800001B681BB1019001F073FF019803A901F05F +:1018100061FF024648B1039B2946204600F098F834 +:10182000002383F3118805B0F0BDFB685A69126884 +:10183000002AF5D01B8A013B1340F1D104F180024C +:10184000EAE70000133138B550F82140ECB13023FD +:1018500083F3118804F58053D3F8A42813685279D0 +:1018600003EB8203DB689B695D6845B10421601866 +:10187000FFF768FE294604F1140001F061FE2046DE +:10188000FFF7B4FE002383F3118838BD70470000D2 +:1018900001F02EB901234022002110B5044600F8C2 +:1018A000303BFFF701FB0023C4E9013310BD00000A +:1018B00010B53023044683F31188242241600021AF +:1018C0000C30FFF7F1FA204601F034F90223002032 +:1018D000237080F3118810BD70B500EB81030546BD +:1018E00050690E461446DA6018B110220021FFF745 +:1018F000DBFAA06918B110220021FFF7D5FA3146B2 +:101900002846BDE8704001F01BBA00008368202221 +:10191000002103F0011310B5044683601030FFF777 +:10192000C3FA2046BDE8104001F096BAF0B4012594 +:1019300000EB810447898D40E4683D43A4694581FB +:1019400023600023A2606360F0BC01F0B3BA000022 +:10195000F0B4012500EB810407898D40E4683D4324 +:101960006469058123600023A2606360F0BC01F01C +:1019700029BB000070B50223002504462422037011 +:101980002946C0F888500C3040F8045CFFF78CFA08 +:10199000204684F8705001F067F963681B6823B132 +:1019A00029462046BDE87040184770BD0378052BD6 +:1019B00010B504460AD080F88C30052303704368C4 +:1019C0001B680BB1042198470023A36010BD0000E1 +:1019D0000178052906D190F88C20436802701B68B5 +:1019E00003B118477047000070B590F87030044696 +:1019F00013B1002380F8703004F18002204601F01A +:101A00004FFA63689B68B3B994F8803013F06005AF +:101A100035D00021204601F041FD0021204601F093 +:101A200031FD63681B6813B10621204698470623E1 +:101A300084F8703070BD204698470028E4D0B4F890 +:101A40008630A26F9A4288BFA36794F98030A56F51 +:101A5000002B4FF0300380F20381002D00F0F28064 +:101A6000092284F8702083F3118800212046D4E9EC +:101A70001D23FFF76DFF002383F31188DAE794F845 +:101A8000812003F07F0343EA022340F202329342B3 +:101A900000F0C58021D8B3F5807F48D00DD8012B48 +:101AA0003FD0022B00F09380002BB2D104F18802CA +:101AB00062670222A267E367C1E7B3F5817F00F0A6 +:101AC0009B80B3F5407FA4D194F88230012BA0D144 +:101AD000B4F8883043F0020332E0B3F5006F4DD024 +:101AE00017D8B3F5A06F31D0A3F5C063012B90D800 +:101AF0006368204694F882205E6894F88310B4F8F6 +:101B00008430B047002884D0436863670368A367C4 +:101B10001AE0B3F5106F36D040F6024293427FF4DC +:101B200078AF5C4B63670223A3670023C3E794F895 +:101B30008230012B7FF46DAFB4F8883023F00203BC +:101B4000A4F88830C4E91D55E56778E7B4F880301B +:101B5000B3F5A06F0ED194F88230204684F88A3015 +:101B600001F0E0F863681B6813B101212046984733 +:101B7000032323700023C4E91D339CE704F18B0386 +:101B800063670123C3E72378042B10D1302383F349 +:101B900011882046FFF7BAFE85F311880321636898 +:101BA00084F88B5021701B680BB12046984794F83D +:101BB0008230002BDED084F88B30042323706368DE +:101BC0001B68002BD6D0022120469847D2E794F814 +:101BD000843020461D0603F00F010AD501F052F9AA +:101BE000012804D002287FF414AF2B4B9AE72B4B2B +:101BF00098E701F039F9F3E794F88230002B7FF48D +:101C000008AF94F8843013F00F01B3D01A062046C1 +:101C100002D501F05BFCADE701F04CFCAAE794F8BB +:101C20008230002B7FF4F5AE94F8843013F00F016E +:101C3000A0D01B06204602D501F030FC9AE701F047 +:101C400021FC97E7142284F8702083F311882B4637 +:101C50002A4629462046FFF769FE85F31188E9E602 +:101C60005DB1152284F8702083F31188002120468D +:101C7000D4E91D23FFF75AFEFDE60B2284F87020FD +:101C800083F311882B462A4629462046FFF760FE3B +:101C9000E3E700BFDC410008D4410008D841000858 +:101CA00038B590F870300446002B3ED0063BDAB2CF +:101CB0000F2A34D80F2B32D8DFE803F03731310840 +:101CC000223231313131313131313737856FB0F82E +:101CD00086309D4214D2C3681B8AB5FBF3F203FB26 +:101CE00012556DB9302383F311882B462A462946B5 +:101CF000FFF72EFE85F311880A2384F870300EE07A +:101D0000142384F87030302383F311880023204695 +:101D10001A461946FFF70AFE002383F3118838BDDF +:101D2000C36F03B198470023E7E70021204601F085 +:101D3000B5FB0021204601F0A5FB63681B6813B1C9 +:101D40000621204698470623D7E7000010B590F8F3 +:101D500070300446142B29D017D8062B05D001D893 +:101D60001BB110BD093B022BFBD80021204601F01E +:101D700095FB0021204601F085FB63681B6813B1C9 +:101D8000062120469847062319E0152BE9D10B239D +:101D900080F87030302383F3118800231A461946E7 +:101DA000FFF7D6FD002383F31188DAE7C3689B6948 +:101DB0005B68002BD5D1C36F03B19847002384F82B +:101DC0007030CEE700238268037503691B68996849 +:101DD0009142FBD25A6803604260106058607047BD +:101DE00000238268037503691B6899689142FBD8D8 +:101DF0005A680360426010605860704708B5084632 +:101E0000302383F311880B7D032B05D0042B0DD0D9 +:101E10002BB983F3118808BD8B6900221A604FF03B +:101E2000FF338361FFF7CEFF0023F2E7D1E90032F1 +:101E300013605A60F3E70000FFF7C4BF054BD96891 +:101E400008751868026853601A600122D86002752C +:101E5000FEF7D8BA402400200C4B30B5DD684B1C8F +:101E600087B004460FD02B46094A684600F04EF969 +:101E70002046FFF7E3FF009B13B1684600F050F9DE +:101E8000A86907B030BDFFF7D9FFF9E7402400206B +:101E9000FD1D0008044B1A68DB6890689B68984237 +:101EA00094BF00200120704740240020084B10B54B +:101EB0001C68D868226853601A600122DC602275B1 +:101EC000FFF78EFF01462046BDE81040FEF79ABAA4 +:101ED0004024002038B5074C012300250649074857 +:101EE0002370656001F0E8FC0223237085F31188FC +:101EF00038BD00BFA8260020E4410008402400208F +:101F000000F044B9034A516853685B1A9842FBD801 +:101F1000704700BF001000E08B6002230861084694 +:101F20008B8270478368A3F1840243F8142C026902 +:101F300043F8442C426943F8402C094A43F8242CC6 +:101F4000C268A3F1200043F8182C022203F80C2CDD +:101F5000002203F80B2C034A43F8102C704700BFF3 +:101F60001D0400084024002008B5FFF7DBFFBDE892 +:101F70000840FFF761BF0000024BDB6898610F204B +:101F8000FFF75CBF40240020302383F31188FFF764 +:101F9000F3BF000008B50146302383F31188082001 +:101FA000FFF75AFF002383F3118808BD064BDB6857 +:101FB00039B1426818605A60136043600420FFF72B +:101FC0004BBF4FF0FF307047402400200368984219 +:101FD00006D01A680260506018469961FFF72CBF5E +:101FE0007047000038B504460D462068844200D191 +:101FF00038BD036823605C608561FFF71DFFF4E76F +:10200000036810B59C68A2420CD85C688A600B60BB +:102010004C602160596099688A1A9A604FF0FF33CA +:10202000836010BD121B1B68ECE700000A2938BF53 +:102030000A2170B504460D460A26601901F034FCE9 +:1020400001F01CFC041BA54203D8751C04462E4657 +:10205000F3E70A2E04D90120BDE8704001F06CBC02 +:1020600070BD0000F8B5144B0D460A2A4FF00A0760 +:10207000D96103F11001826038BF0A2241601969F9 +:102080001446016048601861A81801F0FDFB01F0DA +:10209000F5FB431B0646A34206D37C1C28192746A2 +:1020A000354601F001FCF2E70A2F04D90120BDE812 +:1020B000F84001F041BCF8BD40240020F8B50646C8 +:1020C0000D4601F0DBFB0F4A134653F8107F9F4289 +:1020D00006D12A4601463046BDE8F840FFF7C2BFA8 +:1020E000D169BB68441A2C1928BF2C46A34202D9D7 +:1020F0002946FFF79BFF224631460348BDE8F840DA +:10210000FFF77EBF4024002050240020C0E90323B5 +:10211000002310B45DF8044B4361FFF7CFBF00000C +:1021200010B5194C236998420DD08168D0E900326E +:1021300013605A609A680A449A60002303604FF063 +:10214000FF33A36110BD0268234643F8102F53608C +:102150000022026022699A4203D1BDE8104001F0DA +:102160009DBB936881680B44936001F087FB2269F3 +:10217000E1699268441AA242E4D91144BDE81040D2 +:10218000091AFFF753BF00BF402400202DE9F04794 +:10219000DFF8BC8008F110072C4ED8F8105001F081 +:1021A0006DFBD8F81C40AA68031B9A423ED8144421 +:1021B0004FF00009D5E90032C8F81C4013605A609E +:1021C000C5F80090D8F81030B34201D101F066FB99 +:1021D00089F31188D5E9033128469847302383F3E2 +:1021E00011886B69002BD8D001F048FB6A69A0EB1D +:1021F000040982464A450DD2022001F09DFB0022CF +:10220000D8F81030B34208D151462846BDE8F0470F +:10221000FFF728BF121A2244F2E712EB09092946F8 +:10222000384638BF4A46FFF7EBFEB5E7D8F810301E +:10223000B34208D01444C8F81C00211AA960BDE8B4 +:10224000F047FFF7F3BEBDE8F08700BF5024002041 +:102250004024002000207047FEE700007047000087 +:102260004FF0FF307047000002290CD0032904D042 +:102270000129074818BF00207047032A05D80548E0 +:1022800000EBC2007047044870470020704700BF51 +:10229000BC4200083C2200207042000870B59AB091 +:1022A00005460846144601A900F0C2F801A8FEF749 +:1022B000F3FD431C0022C6B25B001046C5E90034A2 +:1022C00023700323023404F8013C01ABD1B2023481 +:1022D0008E4201D81AB070BD13F8011B013204F808 +:1022E000010C04F8021CF1E708B5302383F31188D0 +:1022F0000348FFF749FA002383F3118808BD00BFA4 +:10230000B026002090F8803003F01F02012A07D188 +:1023100090F881200B2A03D10023C0E91D3315E07A +:1023200003F06003202B08D1B0F884302BB990F86B +:102330008120212A03D81F2A04D8FFF707BA222AAE +:10234000EBD0FAE7034A426707228267C36701209E +:10235000704700BF3322002007B5052917D8DFE8F2 +:1023600001F0191603191920302383F31188104A3C +:1023700001210190FFF7B0FA019802210D4AFFF701 +:10238000ABFA0D48FFF7CCF9002383F3118803B0B3 +:102390005DF804FB302383F311880748FFF796F9B3 +:1023A000F2E7302383F311880348FFF7ADF9EBE739 +:1023B0001042000834420008B026002038B50C4D09 +:1023C0000C4C2A460C4904F10800FFF767FF05F1A1 +:1023D000CA0204F110000949FFF760FF05F5CA724F +:1023E00004F118000649BDE83840FFF757BF00BFA9 +:1023F000883F00203C220020F0410008FA410008FC +:102400000542000870B5044608460D46FEF744FD37 +:10241000C6B22046013403780BB9184670BD324667 +:102420002946FEF725FD0028F3D10120F6E700003C +:102430002DE9F84F05460C46FEF72EFD2D49C6B294 +:102440002846FFF7DFFF08B10436F6B22A492846CE +:10245000FFF7D8FF08B11036F6B2632E0DD8DFF8BB +:102460009490DFF894A0DFF89C80DFF89CB0234FB5 +:102470002E7846B92670BDE8F88F29462046BDE87B +:10248000F84F01F0EDBD252E30D1072249462846F0 +:10249000FEF7EEFC70B93B6807350B3444F80B3C93 +:1024A0007B6844F8073C3B8924F8033CBB7A04F87A +:1024B000013CDDE7082251462846FEF7D9FCA8B9C1 +:1024C000A21C0F4B19780232090911F8081002F802 +:1024D000041C13F8011B01F00F015B4511F80810F3 +:1024E00002F8031CEED118340835C1E7013504F8B1 +:1024F000016BBDE7DC42000805420008E442000829 +:1025000000E8F11FF04200080CE8F11FBFF34F8F05 +:10251000044B1A695107FCD1D3F810215207F8D1A6 +:10252000704700BF0020005208B50D4B1B78ABB9B7 +:10253000FFF7ECFF0B4BDA68D10704D50A4A5A6063 +:1025400002F188325A60D3F80C21D20706D5064A28 +:10255000C3F8042102F18832C3F8042108BD00BF8A +:10256000E6410020002000522301674508B5114BC9 +:102570001B78F3B9104B1A69510703D5DA6842F09A +:102580004002DA60D3F81021520705D5D3F80C21A8 +:1025900042F04002C3F80C21FFF7B8FF064BDA689F +:1025A00042F00102DA60D3F80C2142F00102C3F8D4 +:1025B0000C2108BDE6410020002000520F289ABFE0 +:1025C00000F5806040040020704700004FF40030A8 +:1025D00070470000102070470F2808B50BD8FFF790 +:1025E000EDFF00F500330268013204D1043083426C +:1025F000F9D1012008BD0020FCE700000F2838B504 +:1026000005463FD8FFF782FF1F4CFFF78DFF4FF0C5 +:10261000FF3307286361C4F814311DD82361FFF725 +:1026200075FF030243F02403E360E36843F0800393 +:10263000E36023695A07FCD42846FFF767FFFFF7DA +:10264000BDFF4FF4003100F0F5F82846FFF78EFF8C +:10265000BDE83840FFF7C0BFC4F81031FFF756FFA0 +:10266000A0F108031B0243F02403C4F80C31D4F892 +:102670000C3143F08003C4F80C31D4F810315B07FF +:10268000FBD4D9E7002038BD002000522DE9F84FD7 +:1026900005460C46104645EA0203DE0602D000203D +:1026A000BDE8F88F20F01F00DFF8BCB0DFF8BCA059 +:1026B000FFF73AFF04EB0008444503D10120FFF780 +:1026C00055FFEDE720222946204601F0B9FC10B95C +:1026D00020352034F0E72B4605F120021F68791CD5 +:1026E000DDD104339A42F9D105F178431B481C4EE1 +:1026F000B3F5801F1B4B38BF184603F1F80332BFF8 +:10270000D946D1461E46FFF701FF0760A5EB040C32 +:10271000336804F11C0143F002033360231FD9F82E +:10272000007017F00507FAD153F8042F8B424CF8CC +:102730000320F4D1BFF34F8FFFF7E8FE4FF0FF33D4 +:102740002022214603602846336823F002033360C9 +:1027500001F076FC0028BBD03846B0E714210052C7 +:102760000C20005214200052102000521021005260 +:1027700010B5084C237828B11BB9FFF7D5FE01230B +:10278000237010BD002BFCD02070BDE81040FFF777 +:10279000EDBE00BFE64100200244074BD2B210B5A7 +:1027A000904200D110BD441C00B253F8200041F803 +:1027B000040BE0B2F4E700BF504000580E4B30B5B8 +:1027C0001C6F240405D41C6F1C671C6F44F4004468 +:1027D0001C670A4C02442368D2B243F4807323601E +:1027E000074B904200D130BD441C51F8045B00B24D +:1027F00043F82050E0B2F4E7004402580048025881 +:102800005040005807B5012201A90020FFF7C4FF7E +:10281000019803B05DF804FB13B50446FFF7F2FF1F +:10282000A04205D0012201A900200194FFF7C6FFB4 +:1028300002B010BD0144BFF34F8F064B884204D352 +:10284000BFF34F8FBFF36F8F7047C3F85C02203028 +:10285000F4E700BF00ED00E0034B1A681AB9034A21 +:10286000D2F8D0241A607047E84100200040025896 +:1028700008B5FFF7F1FF024B1868C0F3806008BD90 +:10288000E8410020EFF30983054968334A6B22F0E1 +:1028900001024A6383F30988002383F31188704798 +:1028A00000EF00E0302080F3118862B60D4B0E4A35 +:1028B000D96821F4E0610904090C0A430B49DA6084 +:1028C000D3F8FC2042F08072C3F8FC20084AC2F81A +:1028D000B01F116841F0010111602022DA7783F8FE +:1028E0002200704700ED00E00003FA0555CEACC5AC +:1028F000001000E0302310B583F311880E4B5B68A5 +:1029000013F4006314D0F1EE103AEFF309844FF0A2 +:102910008073683CE361094BDB6B236684F30988B1 +:10292000FFF7B8FA10B1064BA36110BD054BFBE7EA +:1029300083F31188F9E700BF00ED00E000EF00E04D +:102940002F0400083204000870B5BFF34F8FBFF3A7 +:102950006F8F1A4A0021C2F85012BFF34F8FBFF396 +:102960006F8F536943F400335361BFF34F8FBFF34D +:102970006F8FC2F88410BFF34F8FD2F8803043F6C8 +:10298000E074C3F3C900C3F34E335B0103EA0406EA +:10299000014646EA81750139C2F86052F9D2203BFE +:1029A00013F1200FF2D1BFF34F8F536943F48033FB +:1029B0005361BFF34F8FBFF36F8F70BD00ED00E029 +:1029C000FEE70000214B2248224A70B5904237D3DF +:1029D000214BC11EDA1C121A22F003028B4238BFAF +:1029E00000220021FEF760FA1C4A0023C2F884305E +:1029F000BFF34F8FD2F8803043F6E074C3F3C900C1 +:102A0000C3F34E335B0103EA0406014646EA8175CF +:102A10000139C2F86C52F9D2203B13F1200FF2D1E8 +:102A2000BFF34F8FBFF36F8FBFF34F8FBFF36F8F26 +:102A30000023C2F85032BFF34F8FBFF36F8F70BDCA +:102A400053F8041B40F8041BC0E700BFDC44000837 +:102A5000BC430020BC430020BC43002000ED00E04C +:102A6000074BD3F8D81021EA0001C3F8D810D3F8E7 +:102A7000002122EA0002C3F80021D3F80031704798 +:102A80000044025870B5D0E9244300224FF0FF35CE +:102A90009E6804EB42135101D3F80009002805DABF +:102AA000D3F8000940F08040C3F80009D3F8000BC8 +:102AB000002805DAD3F8000B40F08040C3F8000B83 +:102AC000013263189642C3F80859C3F8085BE0D294 +:102AD0004FF00113C4F81C3870BD0000890141F0AB +:102AE0002001016103699B06FCD41220FFF70ABA9A +:102AF00010B50A4C2046FEF7CDFE094BC4F89030C5 +:102B0000084BC4F89430084C2046FEF7C3FE074B30 +:102B1000C4F89030064BC4F8943010BDEC4100204E +:102B200000000840284300088842002000000440BC +:102B30003443000870B503780546012B5CD1434B44 +:102B4000D0F89040984258D1414B0E216520D3F8DF +:102B5000D82042F00062C3F8D820D3F8002142F018 +:102B60000062C3F80021D3F80021D3F8802042F09E +:102B70000062C3F88020D3F8802022F00062C3F8FE +:102B80008020D3F88030FEF7B1FC324BE360324B4B +:102B9000C4F800380023D5F89060C4F8003EC02384 +:102BA00023604FF40413A3633369002BFCDA012381 +:102BB0000C203361FFF7A6F93369DB07FCD4122040 +:102BC000FFF7A0F93369002BFCDA00262846A6603F +:102BD000FFF758FF6B68C4F81068DB68C4F8146826 +:102BE000C4F81C6883BB1D4BA3614FF0FF336361C6 +:102BF000A36843F00103A36070BD194B9842C9D18B +:102C0000134B4FF08060D3F8D82042F00072C3F825 +:102C1000D820D3F8002142F00072C3F80021D3F885 +:102C20000021D3F8802042F00072C3F88020D3F84E +:102C3000802022F00072C3F88020D3F88030FFF7A4 +:102C40000FFF0E214D209EE7064BCDE7EC41002003 +:102C5000004402584014004003002002003C30C0F1 +:102C600088420020083C30C0F8B5D0F890400546B6 +:102C700000214FF000662046FFF730FFD5F8941092 +:102C800000234FF001128F684FF0FF30C4F8343842 +:102C9000C4F81C2804EB431201339F42C2F80069B8 +:102CA000C2F8006BC2F80809C2F8080BF2D20B6830 +:102CB000D5F89020C5F89830636210231361166927 +:102CC00016F01006FBD11220FFF71CF9D4F80038DB +:102CD00023F4FE63C4F80038A36943F4402343F0AF +:102CE0001003A3610923C4F81038C4F814380B4B3F +:102CF000EB604FF0C043C4F8103B094BC4F8003BF5 +:102D0000C4F81069C4F80039D5F8983003F11002FE +:102D100043F48013C5F89820A362F8BD044300086B +:102D200040800010D0F8902090F88A10D2F8003837 +:102D300023F4FE6343EA0113C2F800387047000031 +:102D40002DE9F84300EB8103D0F890500C46804603 +:102D5000DA680FFA81F94801166806F00306731E57 +:102D6000022B05EB41134FF0000194BFB604384E1F +:102D7000C3F8101B4FF0010104F1100398BF06F1D6 +:102D8000805601FA03F3916998BF06F500460029C1 +:102D90003AD0578A04F15801374349016F50D5F8AA +:102DA0001C180B430021C5F81C382B180127C3F849 +:102DB0001019A7405369611E9BB3138A928B9B081D +:102DC000012A88BF5343D8F89820981842EA034351 +:102DD00001F140022146C8F89800284605EB82021E +:102DE0005360FFF77BFE08EB8900C3681B8A43EA48 +:102DF000845348341E4364012E51D5F81C381F43B8 +:102E0000C5F81C78BDE8F88305EB4917D7F8001B17 +:102E100021F40041C7F8001BD5F81C1821EA030370 +:102E2000C0E704F13F030B4A2846214605EB830324 +:102E30005A60FFF753FE05EB4910D0F8003923F430 +:102E40000043C0F80039D5F81C3823EA0707D7E754 +:102E50000080001000040002D0F894201268C0F82E +:102E60009820FFF70FBE00005831D0F8903049018C +:102E70005B5813F4004004D013F4001F0CBF022071 +:102E8000012070474831D0F8903049015B5813F465 +:102E9000004004D013F4001F0CBF02200120704733 +:102EA00000EB8101CB68196A0B6813604B685360B3 +:102EB0007047000000EB810330B5DD68AA69136834 +:102EC000D36019B9402B84BF402313606B8A146808 +:102ED000D0F890201C4402EB4110013C09B2B4FB35 +:102EE000F3F46343033323F0030343EAC44343F09F +:102EF000C043C0F8103B2B6803F00303012B0ED135 +:102F0000D2F8083802EB411013F4807FD0F8003B70 +:102F100014BF43F0805343F00053C0F8003B02EB72 +:102F20004112D2F8003B43F00443C2F8003B30BDED +:102F30002DE9F041D0F8906005460C4606EB4113B0 +:102F4000D3F8087B3A07C3F8087B08D5D6F81438BD +:102F50001B0704D500EB8103DB685B689847FA0721 +:102F60001FD5D6F81438DB071BD505EB8403D968C9 +:102F7000CCB98B69488A5A68B2FBF0F600FB16227E +:102F80008AB91868DA6890420DD2121AC3E900248F +:102F9000302383F3118821462846FFF78BFF84F303 +:102FA0001188BDE8F081012303FA04F26B8923EA5A +:102FB00002036B81CB68002BF3D021462846BDE885 +:102FC000F041184700EB81034A0170B5DD68D0F885 +:102FD00090306C692668E66056BB1A444FF40020B6 +:102FE000C2F810092A6802F00302012A0AB20ED1BF +:102FF000D3F8080803EB421410F4807FD4F80009DA +:1030000014BF40F0805040F00050C4F8000903EBBA +:103010004212D2F8000940F00440C2F8000901222F +:10302000D3F8340802FA01F10143C3F8341870BD33 +:1030300019B9402E84BF4020206020681A442E8A8F +:103040008419013CB4FBF6F440EAC44040F000505F +:10305000C6E700002DE9F843D0F8906005460C461D +:103060004F0106EB4113D3F8088918F0010FC3F89C +:1030700008891CD0D6F81038DB0718D500EB81037F +:10308000D3F80CC0DCF81430D3F800E0DA689645C9 +:1030900030D2A2EB0E024FF000091A60C3F8049080 +:1030A000302383F31188FFF78DFF89F3118818F01F +:1030B000800F1DD0D6F834380126A640334217D0F1 +:1030C00005EB84030134D5F89050D3F80CC0E4B27A +:1030D0002F44DCF8142005EB0434D2F800E05168EA +:1030E000714514D3D5F8343823EA0606C5F8346898 +:1030F000BDE8F883012303FA01F2038923EA0203FE +:103100000381DCF80830002BD1D09847CFE7AEEB35 +:103110000103BCF81000834228BF0346D7F8180902 +:1031200080B2B3EB800FE3D89068A0F1040959F89E +:10313000048FC4F80080A0EB09089844B8F1040F8C +:10314000F5D818440B4490605360C8E72DE9F84F58 +:10315000D0F8905004466E69AB691E4016F4805852 +:103160006E6103D0BDE8F84FFEF704BC002E12DA02 +:10317000D5F8003E9B0705D0D5F8003E23F00303A9 +:10318000C5F8003ED5F80438204623F00103C5F801 +:103190000438FEF71DFC370505D52046FFF772FC05 +:1031A0002046FEF703FCB0040CD5D5F8083813F020 +:1031B000060FEB6823F470530CBF43F4105343F431 +:1031C000A053EB6031071BD56368DB681BB9AB69A3 +:1031D00023F00803AB612378052B0CD1D5F8003E12 +:1031E0009A0705D0D5F8003E23F00303C5F8003E4A +:1031F0002046FEF7EDFB6368DB680BB1204698477D +:10320000F30200F1BA80B70226D5D4F890900027D7 +:103210004FF0010A09EB4712D2F8003B03F44023B8 +:10322000B3F5802F11D1D2F8003B002B0DDA628963 +:103230000AFA07F322EA0303638104EB8703DB68DE +:10324000DB6813B13946204698470137D4F89430EB +:10325000FFB29B689F42DDD9F00619D5D4F89000E3 +:10326000026AC2F30A1702F00F0302F4F012B2F579 +:10327000802F00F0CA80B2F5402F09D104EB830300 +:10328000002200F58050DB681B6A974240F0B08056 +:103290003003D5F8185835D5E90303D50021204669 +:1032A000FFF746FEAA0303D501212046FFF740FEA3 +:1032B0006B0303D502212046FFF73AFE2F0303D507 +:1032C00003212046FFF734FEE80203D504212046FF +:1032D000FFF72EFEA90203D505212046FFF728FEA1 +:1032E0006A0203D506212046FFF722FE2B0203D5F2 +:1032F00007212046FFF71CFEEF0103D508212046D9 +:10330000FFF716FE700340F1A780E90703D50021FF +:103310002046FFF79FFEAA0703D501212046FFF7AD +:1033200099FE6B0703D502212046FFF793FE2F0776 +:1033300003D503212046FFF78DFEEE0603D50421B9 +:103340002046FFF787FEA80603D505212046FFF794 +:1033500081FE690603D506212046FFF77BFE2A067B +:1033600003D507212046FFF775FEEB0574D52046EF +:103370000821BDE8F84FFFF76DBED4F890904FF0EC +:10338000000B4FF0010AD4F894305FFA8BF79B687A +:103390009F423FF638AF09EB4713D3F8002902F4F8 +:1033A0004022B2F5802F20D1D3F80029002A1CDA60 +:1033B000D3F8002942F09042C3F80029D3F800293D +:1033C000002AFBDB3946D4F89000FFF787FB2289FF +:1033D0000AFA07F322EA0303238104EB8703DB687D +:1033E0009B6813B13946204698470BF1010BCAE799 +:1033F000910701D1D0F80080072A02F101029CBF99 +:1034000003F8018B4FEA18283FE704EB830300F52C +:103410008050DA68D2F818C0DCF80820DCE9001C1B +:10342000A1EB0C0C00218F4208D1DB689B699A68E4 +:103430003A449A605A683A445A6029E711F0030FF7 +:1034400001D1D0F800808C4501F1010184BF02F860 +:10345000018B4FEA1828E6E7BDE8F88F08B5034866 +:10346000FFF774FEBDE80840FFF744BAEC410020C6 +:1034700008B50348FFF76AFEBDE80840FFF73ABA0F +:1034800088420020D0F8903003EB4111D1F8003B86 +:1034900043F40013C1F8003B70470000D0F89030AF +:1034A00003EB4111D1F8003943F40013C1F800399E +:1034B00070470000D0F8903003EB4111D1F8003B89 +:1034C00023F40013C1F8003B70470000D0F890309F +:1034D00003EB4111D1F8003923F40013C1F800398E +:1034E0007047000030B50433039C0172002104FBD7 +:1034F0000325C160C0E90653049B0363059BC0E933 +:103500000000C0E90422C0E90842C0E90A1143638F +:1035100030BD00000022416AC260C0E90411C0E968 +:103520000A226FF00101FEF75DBD0000D0E9043210 +:10353000934201D1C2680AB9181D70470020704734 +:10354000036919600021C2680132C260C269134474 +:1035500082699342036124BF436A0361FEF736BD6B +:1035600038B504460D46E3683BB162690020131D7F +:103570001268A3621344E36207E0237A33B9294651 +:103580002046FEF713FD0028EDDA38BD6FF001008C +:10359000FBE70000C368C269013BC3604369134491 +:1035A00082699342436124BF436A4361002383627B +:1035B000036B03B11847704770B53023044683F39B +:1035C0001188866A3EB9FFF7CBFF054618B186F32E +:1035D0001188284670BDA36AE26A13F8015B934222 +:1035E000A36202D32046FFF7D5FF002383F311889F +:1035F000EFE700002DE9F84F04460E4617469846BF +:103600004FF0300989F311880025AA46D4F828B074 +:10361000BBF1000F09D141462046FFF7A1FF20B1C1 +:103620008BF311882846BDE8F88FD4E90A12A7EB7E +:10363000050B521A934528BF9346BBF1400F1BD987 +:10364000334601F1400251F8040B914243F8040B58 +:10365000F9D1A36A403640354033A362D4E90A2346 +:103660009A4202D32046FFF795FF8AF31188BD42A4 +:10367000D8D289F31188C9E730465A46FDF7EEFBE8 +:10368000A36A5E445D445B44A362E7E710B5029C15 +:103690000433017203FB0421C460C0E90613002354 +:1036A000C0E90A33039B0363049BC0E90000C0E93F +:1036B0000422C0E90842436310BD0000026A6FF0B3 +:1036C0000101C260426AC0E904220022C0E90A2264 +:1036D000FEF788BCD0E904239A4201D1C26822B91E +:1036E000184650F8043B0B60704700231846FAE771 +:1036F000C3680021C2690133C3604369134482690E +:103700009342436124BF436A4361FEF75FBC0000FC +:1037100038B504460D46E3683BB1236900201A1D05 +:10372000A262E2691344E36207E0237A33B92946CF +:103730002046FEF73BFC0028EDDA38BD6FF00100B3 +:10374000FBE7000003691960C268013AC260C26900 +:10375000134482699342036124BF436A03610023D7 +:103760008362036B03B118477047000070B53023C4 +:103770000D460446114683F31188866A2EB9FFF779 +:10378000C7FF10B186F3118870BDA36A1D70A36ACC +:10379000E26A01339342A36204D3E169204604390B +:1037A000FFF7D0FF002080F31188EDE72DE9F84FF7 +:1037B00004460D46904699464FF0300A8AF3118828 +:1037C0000026B346A76A4FB949462046FFF7A0FF37 +:1037D00020B187F311883046BDE8F88FD4E90A0795 +:1037E0003A1AA8EB0607974228BF1746402F1BD965 +:1037F00005F1400355F8042B9D4240F8042BF9D104 +:10380000A36A40364033A362D4E90A239A4204D320 +:10381000E16920460439FFF795FF8BF3118846458F +:10382000D9D28AF31188CDE729463A46FDF716FB2F +:10383000A36A3D443E443B44A362E5E7D0E9042348 +:103840009A4217D1C3689BB1836A8BB1043B9B1A20 +:103850000ED01360C368013BC360C3691A44836917 +:103860009A42026124BF436A0361002383620123F9 +:10387000184670470023FBE700F024B9014B586A53 +:10388000704700BF000C0040034B002258631A61D0 +:103890000222DA60704700BF000C0040014B00229A +:1038A000DA607047000C0040014B5863704700BF5E +:1038B000000C0040FEE7000070B51B4B00250446DD +:1038C00086B058600E4685620163FEF7EBFF04F197 +:1038D0001003A560E562C4E904334FF0FF33C4E987 +:1038E0000044C4E90635FFF7C9FF2B46024604F140 +:1038F00034012046C4E9082380230C4A2565FEF7DD +:103900000BFB01230A4AE060009203756846726867 +:103910000192B268CDE90223064BCDE90435FEF7EA +:1039200023FB06B070BD00BFA8260020404300085E +:1039300045430008B5380008024AD36A1843D062EC +:10394000704700BF402400204B6843608B68836051 +:10395000CB68C3600B6943614B6903628B69436247 +:103960000B6803607047000008B53C4B40F2FF71E4 +:103970003B48D3F888200A43C3F88820D3F888202E +:1039800022F4FF6222F00702C3F88820D3F88820CF +:10399000D3F8E0200A43C3F8E020D3F808210A4313 +:1039A000C3F808212F4AD3F808311146FFF7CCFF9E +:1039B00000F5806002F11C01FFF7C6FF00F5806092 +:1039C00002F13801FFF7C0FF00F5806002F15401F9 +:1039D000FFF7BAFF00F5806002F17001FFF7B4FF56 +:1039E00000F5806002F18C01FFF7AEFF00F580600A +:1039F00002F1A801FFF7A8FF00F5806002F1C40101 +:103A0000FFF7A2FF00F5806002F1E001FFF79CFFE5 +:103A100000F5806002F1FC01FFF796FF02F58C7162 +:103A200000F58060FFF790FF00F018F90E4BD3F817 +:103A3000902242F00102C3F89022D3F8942242F07F +:103A40000102C3F894220522C3F898204FF0605277 +:103A5000C3F89C20054AC3F8A02008BD00440258C2 +:103A6000000002584C43000800ED00E01F0008036E +:103A700008B500F0C7FAFEF72DFA0F4BD3F8DC209B +:103A800042F04002C3F8DC20D3F8042122F04002C7 +:103A9000C3F80421D3F80431084B1A6842F0080235 +:103AA0001A601A6842F004021A60FEF7D5FEBDE8FB +:103AB0000840FEF783BC00BF0044025800180248CB +:103AC00070470000114BD3F8E82042F00802C3F819 +:103AD000E820D3F8102142F00802C3F810210C4A64 +:103AE000D3F81031D36B43F00803D363C722094BDB +:103AF0009A624FF0FF32DA6200229A615A63DA600A +:103B00005A6001225A611A60704700BF004402588F +:103B10000010005C000C0040094A08B51169D36828 +:103B20000B40D9B29B076FEA0101116107D5302321 +:103B300083F31188FEF7E4F9002383F3118808BDAD +:103B4000000C0040064BD3F8DC200243C3F8DC2015 +:103B5000D3F804211043C3F80401D3F804317047AB +:103B60000044025808B53C4B4FF0FF31D3F8802099 +:103B700062F00042C3F88020D3F8802002F00042B7 +:103B8000C3F88020D3F88020D3F88420C3F88410B1 +:103B9000D3F884200022C3F88420D3F88400D86F9F +:103BA00040F0FF4040F4FF0040F4DF4040F07F0071 +:103BB000D867D86F20F0FF4020F4FF0020F4DF40EA +:103BC00020F07F00D867D86FD3F888006FEA4050A4 +:103BD0006FEA5050C3F88800D3F88800C0F30A0099 +:103BE000C3F88800D3F88800D3F89000C3F8901089 +:103BF000D3F89000C3F89020D3F89000D3F8940045 +:103C0000C3F89410D3F89400C3F89420D3F8940028 +:103C1000D3F89800C3F89810D3F89800C3F8982008 +:103C2000D3F89800D3F88C00C3F88C10D3F88C002C +:103C3000C3F88C20D3F88C00D3F89C00C3F89C10F8 +:103C4000D3F89C10C3F89C20D3F89C30FDF772FB8E +:103C5000BDE8084000F0AEB90044025808B50122A2 +:103C6000534BC3F80821534BD3F8F42042F002021F +:103C7000C3F8F420D3F81C2142F00202C3F81C213F +:103C80000222D3F81C314C4BDA605A689104FCD5FF +:103C90004A4A1A6001229A60494ADA6000221A618F +:103CA0004FF440429A61444B9A699204FCD51A68D9 +:103CB00042F480721A603F4B1A6F12F4407F04D0B6 +:103CC0004FF480321A6700221A671A6842F0010224 +:103CD0001A60384B1A685007FCD500221A611A691D +:103CE00012F03802FBD1012119604FF08041596078 +:103CF0005A67344ADA62344A1A611A6842F48032E6 +:103D00001A602C4B1A689103FCD51A6842F4805251 +:103D10001A601A689204FCD52C4A2D499A62002236 +:103D20005A63196301F57C01DA6301F2E7119963C3 +:103D30005A64284A1A64284ADA621A6842F0A85279 +:103D40001A601C4B1A6802F02852B2F1285FF9D1B0 +:103D500048229A614FF48862DA6140221A621F4A4F +:103D6000DA641F4A1A651F4A5A651F4A9A65322348 +:103D70001E4A1360136803F00F03022BFAD10D4A99 +:103D8000136943F003031361136903F03803182B1D +:103D9000FAD14FF00050FFF7D5FE4FF08040FFF70B +:103DA000D1FE4FF00040BDE80840FFF7CBBE00BF9A +:103DB00000800051004402580048025800C000F042 +:103DC000020000010000FF0100889008121020008E +:103DD00063020901470E0508DD0BBF01200000202A +:103DE000000001100910E000000101100020005245 +:103DF0004FF0B04208B5D2F8883003F00103C2F8A2 +:103E0000883023B1044A13680BB150689847BDE865 +:103E10000840FEF76FBD00BF3C4300204FF0B042AA +:103E200008B5D2F8883003F00203C2F8883023B115 +:103E3000044A93680BB1D0689847BDE80840FEF784 +:103E400059BD00BF3C4300204FF0B04208B5D2F846 +:103E5000883003F00403C2F8883023B1044A1369A0 +:103E60000BB150699847BDE80840FEF743BD00BF5D +:103E70003C4300204FF0B04208B5D2F8883003F040 +:103E80000803C2F8883023B1044A93690BB1D069A2 +:103E90009847BDE80840FEF72DBD00BF3C43002019 +:103EA0004FF0B04208B5D2F8883003F01003C2F8E2 +:103EB000883023B1044A136A0BB1506A9847BDE8B1 +:103EC0000840FEF717BD00BF3C4300204FF0B04351 +:103ED00010B5D3F8884004F47872C3F88820A3069C +:103EE00004D5124A936A0BB1D06A9847600604D58C +:103EF0000E4A136B0BB1506B9847210604D50B4A41 +:103F0000936B0BB1D06B9847E20504D5074A136C4D +:103F10000BB1506C9847A30504D5044A936C0BB1C0 +:103F2000D06C9847BDE81040FEF7E4BC3C4300204D +:103F30004FF0B04310B5D3F8884004F47C42C3F886 +:103F40008820620504D5164A136D0BB1506D984751 +:103F5000230504D5124A936D0BB1D06D9847E00448 +:103F600004D50F4A136E0BB1506E9847A10404D5C7 +:103F70000B4A936E0BB1D06E9847620404D5084A81 +:103F8000136F0BB1506F9847230404D5044A936F05 +:103F90000BB1D06F9847BDE81040FEF7ABBC00BF37 +:103FA0003C43002008B5FFF7B7FDBDE80840FEF729 +:103FB000A1BC0000062108B50846FDF797FA0621C6 +:103FC0000720FDF793FA06210820FDF78FFA062156 +:103FD0000920FDF78BFA06210A20FDF787FA062152 +:103FE0001720FDF783FA06212820FDF77FFA092123 +:103FF0007A20FDF77BFA07213220BDE80840FDF763 +:1040000075BA000008B5FFF7ADFD00F00BF8FDF73D +:104010003FFCFDF711FBFFF753FDBDE80840FFF73C +:104020002BBC00000023054A19460133102BC2E9BE +:10403000001102F10802F8D1704700BF3C43002094 +:1040400010B501390244904201D1002005E0037807 +:1040500011F8014FA34201D0181B10BD0130F2E747 +:10406000034611F8012B03F8012B002AF9D1704700 +:1040700053544D333248373F3F3F0053544D333252 +:10408000483733782F3732780053544D333248371E +:1040900034332F3735332F373530000001105A00B5 +:1040A0000310590001205800032056001000024060 +:1040B000080002400008024000000B0028000240F7 +:1040C000080002400408024006010C0040000240C3 +:1040D000080002400808024010020D00580002408B +:1040E000080002400C08024016030E007000024057 +:1040F0000C0002401008024000040F00880002403B +:104100000C0002401408024006051000A000024006 +:104110000C0002401808024010061100B8000240CE +:104120000C0002401C08024016072F001004024039 +:104130000804024020080240000838002804024019 +:1041400008040240240802400609390040040240E5 +:104150000804024028080240100A3A0058040240AD +:10416000080402402C080240160B3B007004024079 +:104170000C04024030080240000C3C00880402405D +:104180000C04024034080240060D4400A004024022 +:104190000C04024038080240100E4500B8040240EA +:1041A0000C0402403C080240160F460000000000CC +:1041B000B5150008A1150008DD150008C91500088F +:1041C000D5150008C1150008AD150008991500089F +:1041D000E9150008000000000100000000000000D8 +:1041E00063300000E041000898240020A826002049 +:1041F0004172647550696C6F740025424F4152449E +:10420000252D424C002553455249414C25000000C4 +:104210000200000000000000D51700084518000843 +:1042200040004000583F0020683F0020020000008E +:104230000000000003000000000000008D180008CE +:104240000000000010000000783F00200000000087 +:104250000100000000000000EC410020010102000C +:10426000592300086922000805230008E9220008F4 +:10427000430000007842000809024300020100C028 +:1042800032090400000102020100052400100105AA +:10429000240100010424020205240600010705820E +:1042A000030800FF09040100020A000000070501DD +:1042B00002400000070581024000000012000000DB +:1042C000C4420008120110010200004009124157C7 +:1042D00000020102030100000403090425424F41CA +:1042E0005244250053444D4F44454C483756320004 +:1042F000303132333435363738394142434445461C +:104300000000000000000000E9190008A11C0008DE +:104310004D1D00084000400024430020244300209D +:104320000100000034430020800000004001000034 +:10433000080000000001000000100000080000005C +:104340006D61696E0069646C650000000001802A7F +:1043500000000000AAAAAAAA00010024FFFF000092 +:104360000000000000A00A00000040010000000062 +:10437000AAAAAAAA00000001FFFF00000000000096 +:10438000000000001000000400000000AAAAAAAA71 +:1043900000000008FBDF000000000000000000003B +:1043A0000000000000000000AAAAAAAA0000000065 +:1043B000FFFF0000000000000000000000010000FE +:1043C00000000000AAAAAAAA00010000FFFF000046 +:1043D00000000000000000000000000000000000DD +:1043E000AAAAAAAA00000000FFFF00000000000027 +:1043F000000000000000000000000000AAAAAAAA15 +:1044000000000000FFFF00000000000000000000AE +:104410000000000000000000AAAAAAAA00000000F4 +:10442000FFFF00000000000000000000000000008E +:1044300000000000AAAAAAAA00000000FFFF0000D6 +:10444000000000000000000000000000000000006C +:10445000AAAAAAAA00000000FFFF000000000000B6 +:10446000000000000000000000000000AAAAAAAAA4 +:1044700000000000FFFF000000000000000000003E +:104480008F0400000000000000001A00000000007F +:10449000FF000000000000007040000883040000DE +:1044A0007B4000085004000089400008009600008E +:1044B0000000080096000000000800000400000052 +:1044C000D8420008000000000000000000000000CA +:0C44D000000000000000000000000000E0 +:00000001FF diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 6486b007d6452..75fb19bea15e7 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -52,7 +52,7 @@ echo "Checking CLI Tools installed..." ERROR=$(xcode-select --install 2>&1 > /dev/null) } || { -if [[ $ERROR != *"command line tools are already installed"* ]]; then +if [[ $ERROR != *"ommand line tools are already installed"* ]]; then echo "$ERROR" 1>&2 exit 1 fi diff --git a/Tools/ros2/ardupilot_sitl/config/default_params/dds_udp.parm b/Tools/ros2/ardupilot_sitl/config/default_params/dds_udp.parm index 81c3e69cd9e15..406d0b13f8278 100644 --- a/Tools/ros2/ardupilot_sitl/config/default_params/dds_udp.parm +++ b/Tools/ros2/ardupilot_sitl/config/default_params/dds_udp.parm @@ -1,2 +1,2 @@ DDS_ENABLE 1 -DDS_PORT 2019 +DDS_UDP_PORT 2019 diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 4dbc66c4bff61..7e63f599ae13e 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -428,7 +428,7 @@ for t in $CI_BUILD_TARGET; do echo "Building signed firmwares" sudo apt-get update sudo apt-get install -y python3-dev - python3 -m pip install pymonocypher + python3 -m pip install pymonocypher==3.1.3.2 ./Tools/scripts/signing/generate_keys.py testkey $waf configure --board CubeOrange-ODID --signed-fw --private-key testkey_private_key.dat $waf copter diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index e82241ab3c5d4..61265b77c3724 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1231,7 +1231,7 @@ void AC_PosControl::lean_angles_to_accel_xy(float& accel_x_cmss, float& accel_y_ } // calculate_yaw_and_rate_yaw - update the calculated the vehicle yaw and rate of yaw. -bool AC_PosControl::calculate_yaw_and_rate_yaw() +void AC_PosControl::calculate_yaw_and_rate_yaw() { // Calculate the turn rate float turn_rate = 0.0f; @@ -1250,9 +1250,12 @@ bool AC_PosControl::calculate_yaw_and_rate_yaw() if (vel_desired_xy_len > _vel_max_xy_cms * 0.05f) { _yaw_target = degrees(_vel_desired.xy().angle()) * 100.0f; _yaw_rate_target = turn_rate * degrees(100.0f); - return true; + return; } - return false; + + // use the current attitude controller yaw target + _yaw_target = _attitude_control.get_att_target_euler_cd().z; + _yaw_rate_target = 0; } // calculate_overspeed_gain - calculated increased maximum acceleration and jerk if over speed condition is detected diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 8863125ac4c7b..c47eaa8731f2f 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -411,7 +411,7 @@ class AC_PosControl void lean_angles_to_accel_xy(float& accel_x_cmss, float& accel_y_cmss) const; // calculate_yaw_and_rate_yaw - calculate the vehicle yaw and rate of yaw. - bool calculate_yaw_and_rate_yaw(); + void calculate_yaw_and_rate_yaw(); // calculate_overspeed_gain - calculated increased maximum acceleration and jerk if over speed condition is detected float calculate_overspeed_gain(); diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 4c2198c11ac88..aff6c928f86cf 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -286,9 +286,9 @@ class AC_AutoTune LowPassFilterFloat rotation_rate_filt; // filtered rotation rate in radians/second // backup of currently being tuned parameter values - float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_fltt, orig_roll_smax, orig_roll_sp, orig_roll_accel; - float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_fltt, orig_pitch_smax, orig_pitch_sp, orig_pitch_accel; - float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_fltt, orig_yaw_smax, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel; + float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_dff, orig_roll_fltt, orig_roll_smax, orig_roll_sp, orig_roll_accel; + float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_dff, orig_pitch_fltt, orig_pitch_smax, orig_pitch_sp, orig_pitch_accel; + float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_dff, orig_yaw_fltt, orig_yaw_smax, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel; bool orig_bf_feedforward; // currently being tuned parameter values diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index f304c3e70acb9..37d9d3f415bc7 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -149,6 +149,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() orig_roll_ri = attitude_control->get_rate_roll_pid().kI(); orig_roll_rd = attitude_control->get_rate_roll_pid().kD(); orig_roll_rff = attitude_control->get_rate_roll_pid().ff(); + orig_roll_dff = attitude_control->get_rate_roll_pid().kDff(); orig_roll_fltt = attitude_control->get_rate_roll_pid().filt_T_hz(); orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit(); orig_roll_sp = attitude_control->get_angle_roll_p().kP(); @@ -162,6 +163,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI(); orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD(); orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff(); + orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff(); orig_pitch_fltt = attitude_control->get_rate_pitch_pid().filt_T_hz(); orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit(); orig_pitch_sp = attitude_control->get_angle_pitch_p().kP(); @@ -175,6 +177,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI(); orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD(); orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff(); + orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff(); orig_yaw_fltt = attitude_control->get_rate_yaw_pid().filt_T_hz(); orig_yaw_smax = attitude_control->get_rate_yaw_pid().slew_limit(); orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz(); @@ -206,6 +209,7 @@ void AC_AutoTune_Multi::load_orig_gains() attitude_control->get_rate_roll_pid().kI(orig_roll_ri); attitude_control->get_rate_roll_pid().kD(orig_roll_rd); attitude_control->get_rate_roll_pid().ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().kDff(orig_roll_dff); attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax); attitude_control->get_angle_roll_p().kP(orig_roll_sp); @@ -218,6 +222,7 @@ void AC_AutoTune_Multi::load_orig_gains() attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri); attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd); attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff); attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax); attitude_control->get_angle_pitch_p().kP(orig_pitch_sp); @@ -230,6 +235,7 @@ void AC_AutoTune_Multi::load_orig_gains() attitude_control->get_rate_yaw_pid().kI(orig_yaw_ri); attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd); attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff); attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF); attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax); @@ -253,6 +259,7 @@ void AC_AutoTune_Multi::load_tuned_gains() attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL); attitude_control->get_rate_roll_pid().kD(tune_roll_rd); attitude_control->get_rate_roll_pid().ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().kDff(orig_roll_dff); attitude_control->get_angle_roll_p().kP(tune_roll_sp); attitude_control->set_accel_roll_max_cdss(tune_roll_accel); } @@ -263,6 +270,7 @@ void AC_AutoTune_Multi::load_tuned_gains() attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL); attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff); attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel); } @@ -278,6 +286,7 @@ void AC_AutoTune_Multi::load_tuned_gains() attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF); } attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff); attitude_control->get_angle_yaw_p().kP(tune_yaw_sp); attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel); } @@ -296,6 +305,7 @@ void AC_AutoTune_Multi::load_intra_test_gains() attitude_control->get_rate_roll_pid().kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); attitude_control->get_rate_roll_pid().kD(orig_roll_rd); attitude_control->get_rate_roll_pid().ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().kDff(orig_roll_dff); attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax); attitude_control->get_angle_roll_p().kP(orig_roll_sp); @@ -305,6 +315,7 @@ void AC_AutoTune_Multi::load_intra_test_gains() attitude_control->get_rate_pitch_pid().kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd); attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff); attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax); attitude_control->get_angle_pitch_p().kP(orig_pitch_sp); @@ -314,6 +325,7 @@ void AC_AutoTune_Multi::load_intra_test_gains() attitude_control->get_rate_yaw_pid().kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING); attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd); attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff); attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax); attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF); @@ -331,6 +343,7 @@ void AC_AutoTune_Multi::load_test_gains() attitude_control->get_rate_roll_pid().kI(tune_roll_rp*0.01f); attitude_control->get_rate_roll_pid().kD(tune_roll_rd); attitude_control->get_rate_roll_pid().ff(0.0f); + attitude_control->get_rate_roll_pid().kDff(0.0f); attitude_control->get_rate_roll_pid().filt_T_hz(0.0f); attitude_control->get_rate_roll_pid().slew_limit(0.0f); attitude_control->get_angle_roll_p().kP(tune_roll_sp); @@ -340,6 +353,7 @@ void AC_AutoTune_Multi::load_test_gains() attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*0.01f); attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); attitude_control->get_rate_pitch_pid().ff(0.0f); + attitude_control->get_rate_pitch_pid().kDff(0.0f); attitude_control->get_rate_pitch_pid().filt_T_hz(0.0f); attitude_control->get_rate_pitch_pid().slew_limit(0.0f); attitude_control->get_angle_pitch_p().kP(tune_pitch_sp); @@ -349,6 +363,7 @@ void AC_AutoTune_Multi::load_test_gains() attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp); attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f); attitude_control->get_rate_yaw_pid().ff(0.0f); + attitude_control->get_rate_yaw_pid().kDff(0.0f); if (axis == YAW_D) { attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd); } else { @@ -383,6 +398,7 @@ void AC_AutoTune_Multi::save_tuning_gains() attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL); attitude_control->get_rate_roll_pid().kD(tune_roll_rd); attitude_control->get_rate_roll_pid().ff(orig_roll_rff); + attitude_control->get_rate_roll_pid().kDff(orig_roll_dff); attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt); attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax); attitude_control->get_rate_roll_pid().save_gains(); @@ -399,6 +415,7 @@ void AC_AutoTune_Multi::save_tuning_gains() orig_roll_ri = attitude_control->get_rate_roll_pid().kI(); orig_roll_rd = attitude_control->get_rate_roll_pid().kD(); orig_roll_rff = attitude_control->get_rate_roll_pid().ff(); + orig_roll_dff = attitude_control->get_rate_roll_pid().kDff(); orig_roll_sp = attitude_control->get_angle_roll_p().kP(); orig_roll_accel = attitude_control->get_accel_roll_max_cdss(); } @@ -409,6 +426,7 @@ void AC_AutoTune_Multi::save_tuning_gains() attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL); attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd); attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff); + attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff); attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt); attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax); attitude_control->get_rate_pitch_pid().save_gains(); @@ -425,6 +443,7 @@ void AC_AutoTune_Multi::save_tuning_gains() orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI(); orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD(); orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff(); + orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff(); orig_pitch_sp = attitude_control->get_angle_pitch_p().kP(); orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss(); } @@ -435,6 +454,7 @@ void AC_AutoTune_Multi::save_tuning_gains() attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp); attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL); attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff); + attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff); attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt); attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax); if (yaw_d_enabled()) { @@ -457,6 +477,7 @@ void AC_AutoTune_Multi::save_tuning_gains() orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI(); orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD(); orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff(); + orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff(); orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz(); orig_yaw_sp = attitude_control->get_angle_yaw_p().kP(); orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss(); diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 75f0aeb0fc77e..b4484648e26d8 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -76,12 +76,12 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_ROVER), // @Param: BACKUP_SPD - // @DisplayName: Avoidance maximum backup speed - // @Description: Maximum speed that will be used to back away from obstacles in GPS modes (m/s). Set zero to disable + // @DisplayName: Avoidance maximum horizontal backup speed + // @Description: Maximum speed that will be used to back away from obstacles horizontally in position control modes (m/s). Set zero to disable horizontal backup. // @Units: m/s // @Range: 0 2 // @User: Standard - AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_max, 0.75f), + AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_xy_max, 0.75f), // @Param{Copter}: ALT_MIN // @DisplayName: Avoidance minimum altitude @@ -107,6 +107,14 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = { // @User: Standard AP_GROUPINFO("BACKUP_DZ", 9, AC_Avoid, _backup_deadzone, 0.10f), + // @Param: BACKZ_SPD + // @DisplayName: Avoidance maximum vertical backup speed + // @Description: Maximum speed that will be used to back away from obstacles vertically in height control modes (m/s). Set zero to disable vertical backup. + // @Units: m/s + // @Range: 0 2 + // @User: Standard + AP_GROUPINFO("BACKZ_SPD", 10, AC_Avoid, _backup_speed_z_max, 0.75), + AP_GROUPEND }; @@ -220,14 +228,12 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa const float desired_backup_vel_z = back_vel_down + back_vel_up; Vector3f desired_backup_vel{desired_backup_vel_xy.x, desired_backup_vel_xy.y, desired_backup_vel_z}; - const float max_back_spd_cms = _backup_speed_max * 100.0f; - if (!desired_backup_vel.is_zero() && is_positive(max_back_spd_cms)) { + const float max_back_spd_xy_cms = _backup_speed_xy_max * 100.0; + if (!desired_backup_vel.xy().is_zero() && is_positive(max_back_spd_xy_cms)) { backing_up = true; - // Constrain backing away speed - if (desired_backup_vel.length() > max_back_spd_cms) { - desired_backup_vel = desired_backup_vel.normalized() * max_back_spd_cms; - } - + // Constrain horizontal backing away speed + desired_backup_vel.xy().limit_length(max_back_spd_xy_cms); + // let user take control if they are backing away at a greater speed than what we have calculated // this has to be done for x,y,z separately. For eg, user is doing fine in "x" direction but might need backing up in "y". if (!is_zero(desired_backup_vel.x)) { @@ -244,6 +250,15 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa desired_vel_cms.y = MIN(desired_vel_cms.y, desired_backup_vel.y); } } + } + + const float max_back_spd_z_cms = _backup_speed_z_max * 100.0; + if (!is_zero(desired_backup_vel.z) && is_positive(max_back_spd_z_cms)) { + backing_up = true; + + // Constrain vertical backing away speed + desired_backup_vel.z = constrain_float(desired_backup_vel.z, -max_back_spd_z_cms, max_back_spd_z_cms); + if (!is_zero(desired_backup_vel.z)) { if (is_positive(desired_backup_vel.z)) { desired_vel_cms.z = MAX(desired_vel_cms.z, desired_backup_vel.z); @@ -252,6 +267,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa } } } + // limit acceleration limit_accel(desired_vel_cms_original, desired_vel_cms, dt); @@ -418,7 +434,13 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c if (alt_diff <= 0.0f) { climb_rate_cms = MIN(climb_rate_cms, 0.0f); // also calculate backup speed that will get us back to safe altitude - backup_speed = -1*(get_max_speed(kP, accel_cmss_limited, -alt_diff*100.0f, dt)); + const float max_back_spd_cms = _backup_speed_z_max * 100.0; + if (is_positive(max_back_spd_cms)) { + backup_speed = -1*(get_max_speed(kP, accel_cmss_limited, -alt_diff*100.0f, dt)); + + // Constrain to max backup speed + backup_speed = MAX(backup_speed, -max_back_spd_cms); + } return; } diff --git a/libraries/AC_Avoidance/AC_Avoid.h b/libraries/AC_Avoidance/AC_Avoid.h index 6bccfb846d58b..29dca71752d18 100644 --- a/libraries/AC_Avoidance/AC_Avoid.h +++ b/libraries/AC_Avoidance/AC_Avoid.h @@ -207,14 +207,15 @@ class AC_Avoid { // parameters AP_Int8 _enabled; - AP_Int16 _angle_max; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes) - AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes - AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes - AP_Int8 _behavior; // avoidance behaviour (slide or stop) - AP_Float _backup_speed_max; // Maximum speed that will be used to back away (in m/s) - AP_Float _alt_min; // alt below which Proximity based avoidance is turned off - AP_Float _accel_max; // maximum acceleration while simple avoidance is active - AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles + AP_Int16 _angle_max; // maximum lean angle to avoid obstacles (only used in non-GPS flight modes) + AP_Float _dist_max; // distance (in meters) from object at which obstacle avoidance will begin in non-GPS modes + AP_Float _margin; // vehicle will attempt to stay this distance (in meters) from objects while in GPS modes + AP_Int8 _behavior; // avoidance behaviour (slide or stop) + AP_Float _backup_speed_xy_max; // Maximum speed that will be used to back away horizontally (in m/s) + AP_Float _backup_speed_z_max; // Maximum speed that will be used to back away verticality (in m/s) + AP_Float _alt_min; // alt below which Proximity based avoidance is turned off + AP_Float _accel_max; // maximum acceleration while simple avoidance is active + AP_Float _backup_deadzone; // distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles bool _proximity_enabled = true; // true if proximity sensor based avoidance is enabled (used to allow pilot to enable/disable) bool _proximity_alt_enabled = true; // true if proximity sensor based avoidance is enabled based on altitude diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 7bbb27364d51a..23a94c2760302 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -154,6 +154,15 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @User: Advanced AP_GROUPINFO("MAGTHRESH", 10, AP_Arming, magfield_error_threshold, AP_ARMING_MAGFIELD_ERROR_THRESHOLD), +#if AP_ARMING_CRASHDUMP_ACK_ENABLED + // @Param: CRSDP_IGN + // @DisplayName: Disable CrashDump Arming check + // @Description: Must have value "1" if crashdump data is present on the system, or a prearm failure will be raised. Do not set this parameter unless the risks of doing so are fully understood. The presence of a crash dump means that the firmware currently installed has suffered a critical software failure which resulted in the autopilot immediately rebooting. The crashdump file gives diagnostic information which can help in finding the issue, please contact the ArduPIlot support team. If this crashdump data is present, the vehicle is likely unsafe to fly. Check the ArduPilot documentation for more details. + // @Values: 0:Crash Dump arming check active, 1:Crash Dump arming check deactivated + // @User: Advanced + AP_GROUPINFO("CRSDP_IGN", 11, AP_Arming, crashdump_ack.acked, 0), +#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED + AP_GROUPEND }; @@ -180,6 +189,13 @@ AP_Arming::AP_Arming() // performs pre-arm checks. expects to be called at 1hz. void AP_Arming::update(void) { +#if AP_ARMING_CRASHDUMP_ACK_ENABLED + // if we boot with no crashdump data present, reset the "ignore" + // parameter so the user will need to acknowledge future crashes + // too: + crashdump_ack.check_reset(); +#endif + const uint32_t now_ms = AP_HAL::millis(); // perform pre-arm checks & display failures every 30 seconds bool display_fail = false; @@ -197,6 +213,19 @@ void AP_Arming::update(void) pre_arm_checks(display_fail); } +#if AP_ARMING_CRASHDUMP_ACK_ENABLED +void AP_Arming::CrashDump::check_reset() +{ + // if there is no crash dump data then clear the crash dump ack. + // This means on subsequent crash-dumps appearing the user must + // re-acknowledge. + if (hal.util->last_crash_dump_size() == 0) { + // no crash dump data + acked.set_and_save_ifchanged(0); + } +} +#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED + uint16_t AP_Arming::compass_magfield_expected() const { return AP_ARMING_COMPASS_MAGFIELD_EXPECTED; @@ -1637,6 +1666,9 @@ bool AP_Arming::pre_arm_checks(bool report) #endif #if AP_OPENDRONEID_ENABLED & opendroneid_checks(report) +#endif +#if AP_ARMING_CRASHDUMP_ACK_ENABLED + & crashdump_checks(report) #endif & serial_protocol_checks(report) & estop_checks(report); @@ -1689,6 +1721,30 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) return true; } +#if AP_ARMING_CRASHDUMP_ACK_ENABLED +bool AP_Arming::crashdump_checks(bool report) +{ + if (hal.util->last_crash_dump_size() == 0) { + // no crash dump data + return true; + } + + // see if the user has acknowledged the failure and wants to fly anyway: + if (crashdump_ack.acked) { + // they may have acked the problem, that doesn't mean we don't + // continue to warn them they're on thin ice: + if (report) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "CrashDump data detected"); + } + return true; + } + + check_failed(ARMING_CHECK_PARAMETERS, true, "CrashDump data detected"); + + return false; +} +#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED + bool AP_Arming::mandatory_checks(bool report) { bool ret = true; diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 8f46bd47e9d77..36dbe90db04c3 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -3,6 +3,7 @@ #include #include #include +#include #include "AP_Arming_config.h" #include "AP_InertialSensor/AP_InertialSensor_config.h" @@ -230,6 +231,10 @@ class AP_Arming { bool estop_checks(bool display_failure); +#if AP_ARMING_CRASHDUMP_ACK_ENABLED + bool crashdump_checks(bool report); +#endif + virtual bool system_checks(bool report); bool can_checks(bool report); @@ -309,6 +314,14 @@ class AP_Arming { bool report_immediately; // set to true when check goes from true to false, to trigger immediate report void update_arm_gpio(); + +#if AP_ARMING_CRASHDUMP_ACK_ENABLED + struct CrashDump { + void check_reset(); + AP_Int8 acked; + } crashdump_ack; +#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED + }; namespace AP { diff --git a/libraries/AP_Arming/AP_Arming_config.h b/libraries/AP_Arming/AP_Arming_config.h index 748bb498901ec..b600254481da8 100644 --- a/libraries/AP_Arming/AP_Arming_config.h +++ b/libraries/AP_Arming/AP_Arming_config.h @@ -5,3 +5,7 @@ #ifndef AP_ARMING_AUX_AUTH_ENABLED #define AP_ARMING_AUX_AUTH_ENABLED AP_SCRIPTING_ENABLED #endif + +#ifndef AP_ARMING_CRASHDUMP_ACK_ENABLED +#define AP_ARMING_CRASHDUMP_ACK_ENABLED AP_CRASHDUMP_ENABLED +#endif diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index d16d29e441e89..4b2182388b074 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -324,6 +324,29 @@ MAV_RESULT AP_Camera::handle_command(const mavlink_command_int_t &packet) break; } return MAV_RESULT_DENIED; + +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED + case MAV_CMD_SET_CAMERA_SOURCE: + // sanity check instance + if (is_negative(packet.param1) || packet.param1 > AP_CAMERA_MAX_INSTANCES) { + return MAV_RESULT_DENIED; + } + if (is_zero(packet.param1)) { + // set camera source for all backends + bool accepted = false; + for (uint8_t i = 0; i < ARRAY_SIZE(_backends); i++) { + if (_backends[i] != nullptr) { + accepted |= set_camera_source(i, (AP_Camera::CameraSource)packet.param2, (AP_Camera::CameraSource)packet.param3); + } + } + return accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED; + } + if (set_camera_source(packet.param1-1, (AP_Camera::CameraSource)packet.param2, (AP_Camera::CameraSource)packet.param3)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_DENIED; +#endif + case MAV_CMD_IMAGE_START_CAPTURE: // param1 : camera id // param2 : interval (in seconds) @@ -666,6 +689,7 @@ bool AP_Camera::set_tracking(uint8_t instance, TrackingType tracking_type, const return backend->set_tracking(tracking_type, p1, p2); } +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED // set camera lens as a value from 0 to 5 bool AP_Camera::set_lens(uint8_t lens) { @@ -690,6 +714,21 @@ bool AP_Camera::set_lens(uint8_t instance, uint8_t lens) return backend->set_lens(lens); } +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +bool AP_Camera::set_camera_source(uint8_t instance, CameraSource primary_source, CameraSource secondary_source) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + + // call instance + return backend->set_camera_source(primary_source, secondary_source); +} +#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED + #if AP_CAMERA_SCRIPTING_ENABLED // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 71ef3ffda4614..ee9f142cecbb9 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -156,10 +156,23 @@ class AP_Camera { bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2); bool set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2); - // set camera lens as a value from 0 to 5 +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED + // set camera lens as a value from 0 to 5, instance starts from 0 bool set_lens(uint8_t lens); bool set_lens(uint8_t instance, uint8_t lens); + // camera source handling enum. This is a one-to-one mapping with the CAMERA_SOURCE mavlink enum + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + enum class CameraSource { + DEFAULT = 0, + RGB = 1, + IR = 2, + NDVI = 3, + RGB_WIDEANGLE = 4, + }; + bool set_camera_source(uint8_t instance, CameraSource primary_source, CameraSource secondary_source); +#endif + // set if vehicle is in AUTO mode void set_is_auto_mode(bool enable) { _is_in_auto_mode = enable; } diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index b60e06d4dcd14..425b7dc40ff07 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -82,9 +82,14 @@ class AP_Camera_Backend // p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; } +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED // set camera lens as a value from 0 to 5 virtual bool set_lens(uint8_t lens) { return false; } + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + virtual bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) { return false; } +#endif + // get camera image horizontal or vertical field of view in degrees. returns 0 if unknown float horizontal_fov() const { return MAX(0, _params.hfov); } float vertical_fov() const { return MAX(0, _params.vfov); } diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index 775ac53146af8..c3d8669194802 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -70,6 +70,18 @@ bool AP_Camera_Mount::set_lens(uint8_t lens) return false; } +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +bool AP_Camera_Mount::set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) +{ +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->set_camera_source(get_mount_instance(), (uint8_t)primary_source, (uint8_t)secondary_source); + } +#endif + return false; +} + // send camera information message to GCS void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const { diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index c453b96cdd611..56c607fb47f3b 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -54,6 +54,9 @@ class AP_Camera_Mount : public AP_Camera_Backend // set camera lens as a value from 0 to 5 bool set_lens(uint8_t lens) override; + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + bool set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source) override; + // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override; diff --git a/libraries/AP_Camera/AP_Camera_config.h b/libraries/AP_Camera/AP_Camera_config.h index b153c47963948..15b399f003489 100644 --- a/libraries/AP_Camera/AP_Camera_config.h +++ b/libraries/AP_Camera/AP_Camera_config.h @@ -9,10 +9,6 @@ #define AP_CAMERA_ENABLED 1 #endif -#ifndef AP_CAMERA_SEND_FOV_STATUS_ENABLED -#define AP_CAMERA_SEND_FOV_STATUS_ENABLED AP_MOUNT_POI_TO_LATLONALT_ENABLED -#endif - #ifndef AP_CAMERA_BACKEND_DEFAULT_ENABLED #define AP_CAMERA_BACKEND_DEFAULT_ENABLED AP_CAMERA_ENABLED #endif @@ -44,3 +40,12 @@ #ifndef AP_CAMERA_SCRIPTING_ENABLED #define AP_CAMERA_SCRIPTING_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED #endif + +#ifndef AP_CAMERA_SEND_FOV_STATUS_ENABLED +#define AP_CAMERA_SEND_FOV_STATUS_ENABLED AP_MOUNT_POI_TO_LATLONALT_ENABLED +#endif + +// set camera source is supported on cameras that may have more than one lens which is curently only cameras within gimbals/mounts +#ifndef AP_CAMERA_SET_CAMERA_SOURCE_ENABLED +#define AP_CAMERA_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED +#endif diff --git a/libraries/AP_Compass/AP_Compass_IST8310.cpp b/libraries/AP_Compass/AP_Compass_IST8310.cpp index be982a93c6d8c..c2f368ce58a1e 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.cpp +++ b/libraries/AP_Compass/AP_Compass_IST8310.cpp @@ -113,6 +113,22 @@ bool AP_Compass_IST8310::init() // high retries for init _dev->set_retries(10); + /* + unfortunately the IST8310 employs the novel concept of a + writeable WHOAMI register. The register can become corrupt due + to bus noise, and what is worse it persists the corruption even + across a power cycle. If you power it off for 30s or more then + it will reset to the default of 0x10, but for less than that the + value of WAI is unreliable. + + To avoid this issue we do a reset of the device before we probe + the WAI register. This is nasty as we don't yet know we've found + a real IST8310, but it is the best we can do given the bad + hardware design of the sensor + */ + _dev->write_register(CNTL2_REG, CNTL2_VAL_SRST); + hal.scheduler->delay(10); + uint8_t whoami; if (!_dev->read_registers(WAI_REG, &whoami, 1) || whoami != DEVICE_ID) { diff --git a/libraries/AP_DAL/AP_DAL_VisualOdom.h b/libraries/AP_DAL/AP_DAL_VisualOdom.h index 7d50bddfd7f2e..04ba7d5dd7273 100644 --- a/libraries/AP_DAL/AP_DAL_VisualOdom.h +++ b/libraries/AP_DAL/AP_DAL_VisualOdom.h @@ -18,7 +18,7 @@ class AP_DAL_VisualOdom { return RVOH.enabled; } - bool get_delay_ms() const { + uint16_t get_delay_ms() const { return RVOH.delay_ms; } diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index eb038fd68a499..3daa69f6b86e0 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -64,7 +64,7 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] { // @Range: 1 65535 // @RebootRequired: True // @User: Standard - AP_GROUPINFO("_PORT", 2, AP_DDS_Client, udp.port, 2019), + AP_GROUPINFO("_UDP_PORT", 2, AP_DDS_Client, udp.port, 2019), // @Group: _IP // @Path: ../AP_Networking/AP_Networking_address.cpp diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index dc3ff2a34b268..315cc17b22765 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -235,12 +235,14 @@ bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Invalid backend"); return false; } - + if (!backend->pre_arm_check(failure_msg, failure_msg_len)) { + return false; + } if (!state.have_origin) { hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: No origin"); - return false; + return false; } - return backend->pre_arm_check(failure_msg, failure_msg_len); + return true; } /* diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp index d4ee38811c22f..c7ddd1099e2be 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp @@ -45,6 +45,8 @@ #include #include +static const char* LOG_FMT = "%s ExternalAHRS: %s"; + extern const AP_HAL::HAL &hal; AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_frontend, @@ -57,12 +59,12 @@ AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_fro port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); if (!uart) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MicroStrain7 ExternalAHRS no UART"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, LOG_FMT, get_name(), "no UART"); return; } if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_MicroStrain7::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) { - AP_BoardConfig::allocation_error("MicroStrain7 failed to allocate ExternalAHRS update thread"); + AP_BoardConfig::allocation_error("MicroStrain7 ExternalAHRS failed to allocate ExternalAHRS update thread"); } // don't offer IMU by default, at 100Hz it is too slow for many aircraft @@ -71,7 +73,9 @@ AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_fro uint16_t(AP_ExternalAHRS::AvailableSensor::COMPASS)); hal.scheduler->delay(5000); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MicroStrain7 ExternalAHRS initialised"); + if (!initialised()) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, LOG_FMT, get_name(), "failed to initialise."); + } } void AP_ExternalAHRS_MicroStrain7::update_thread(void) @@ -84,9 +88,19 @@ void AP_ExternalAHRS_MicroStrain7::update_thread(void) while (true) { build_packet(); hal.scheduler->delay_microseconds(100); + check_initialise_state(); } } +void AP_ExternalAHRS_MicroStrain7::check_initialise_state(void) +{ + const auto new_init_state = initialised(); + // Only send the message after fully booted up, otherwise it gets dropped. + if (!last_init_state && new_init_state && AP_HAL::millis() > 5000) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, LOG_FMT, get_name(), "initialised."); + last_init_state = new_init_state; + } +} // Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet. @@ -205,20 +219,20 @@ void AP_ExternalAHRS_MicroStrain7::post_filter() const hdop: gnss_data[instance].hdop, vdop: gnss_data[instance].vdop, - longitude: filter_data.lon, - latitude: filter_data.lat, + longitude: gnss_data[instance].lon, + latitude: gnss_data[instance].lat, msl_altitude: gnss_data[instance].msl_altitude, - ned_vel_north: filter_data.ned_velocity_north, - ned_vel_east: filter_data.ned_velocity_east, - ned_vel_down: filter_data.ned_velocity_down, + ned_vel_north: gnss_data[instance].ned_velocity_north, + ned_vel_east: gnss_data[instance].ned_velocity_east, + ned_vel_down: gnss_data[instance].ned_velocity_down, }; // *INDENT-ON* if (gps.fix_type >= 3 && !state.have_origin) { WITH_SEMAPHORE(state.sem); - state.origin = Location{int32_t(filter_data.lat), - int32_t(filter_data.lon), + state.origin = Location{int32_t(gnss_data[instance].lat), + int32_t(gnss_data[instance].lon), int32_t(gnss_data[instance].msl_altitude), Location::AltFrame::ABSOLUTE}; state.have_origin = true; @@ -238,54 +252,45 @@ int8_t AP_ExternalAHRS_MicroStrain7::get_port(void) const // Get model/type name const char* AP_ExternalAHRS_MicroStrain7::get_name() const { - return "MICROSTRAIN7"; + return "MicroStrain7"; } bool AP_ExternalAHRS_MicroStrain7::healthy(void) const { - uint32_t now = AP_HAL::millis(); - - // Expect the following rates: - // * Navigation Filter: 25Hz = 40mS - // * GPS: 2Hz = 500mS - // * IMU: 25Hz = 40mS - - // Allow for some slight variance of 10% - constexpr float RateFoS = 1.1; - - constexpr uint32_t expected_filter_time_delta_ms = 40; - constexpr uint32_t expected_gps_time_delta_ms = 500; - constexpr uint32_t expected_imu_time_delta_ms = 40; - - const bool times_healthy = (now - last_imu_pkt < expected_imu_time_delta_ms * RateFoS && \ - now - last_gps_pkt < expected_gps_time_delta_ms * RateFoS && \ - now - last_filter_pkt < expected_filter_time_delta_ms * RateFoS); - const auto filter_state = static_cast(filter_status.state); - const bool filter_healthy = (filter_state == FilterState::GQ7_FULL_NAV || filter_state == FilterState::GQ7_AHRS); - return times_healthy && filter_healthy; + return times_healthy() && filter_healthy(); } bool AP_ExternalAHRS_MicroStrain7::initialised(void) const { const bool got_packets = last_imu_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0; - const auto filter_state = static_cast(filter_status.state); - const bool filter_healthy = filter_state_healthy(filter_state); - return got_packets && filter_healthy; + return got_packets; } bool AP_ExternalAHRS_MicroStrain7::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const { + if (!initialised()) { + hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "not initialised"); + return false; + } + if (!times_healthy()) { + hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "data is stale"); + return false; + } + if (!filter_healthy()) { + hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "filter is unhealthy"); + return false; + } if (!healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain7 unhealthy"); + hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "unhealthy"); return false; } - // TODO is this necessary? hard coding the first instance. - if (gnss_data[0].fix_type < 3) { - hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain7 no GPS lock"); + static_assert(NUM_GNSS_INSTANCES == 2, "This check only works if there are two GPS types."); + if (gnss_data[0].fix_type < GPS_FIX_TYPE_3D_FIX && gnss_data[1].fix_type < GPS_FIX_TYPE_3D_FIX) { + hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "missing 3D GPS fix on either GPS"); return false; } if (!filter_state_healthy(FilterState(filter_status.state))) { - hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain7 filter not running"); + hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "filter not healthy"); return false; } @@ -361,12 +366,47 @@ void AP_ExternalAHRS_MicroStrain7::send_status_report(GCS_MAVLINK &link) const const float hgt_gate = 4; // represents hz value data is posted at const float mag_var = 0; //we may need to change this to be like the other gates, set to 0 because mag is ignored by the ins filter in vectornav - // TODO fix to use NED filter speed accuracy instead of first gnss - // https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/data/mip_field_filter_ned_vel_uncertainty.htm + const float velocity_variance {filter_data.ned_velocity_uncertainty.length() / vel_gate}; + const float pos_horiz_variance {filter_data.ned_position_uncertainty.xy().length() / pos_gate}; + const float pos_vert_variance {filter_data.ned_position_uncertainty.z / hgt_gate}; + // No terrain alt sensor on MicroStrain7. + const float terrain_alt_variance {0}; + // No airspeed sensor on MicroStrain7. + const float airspeed_variance {0}; mavlink_msg_ekf_status_report_send(link.get_chan(), flags, - gnss_data[0].speed_accuracy/vel_gate, gnss_data[0].horizontal_position_accuracy/pos_gate, gnss_data[0].vertical_position_accuracy/hgt_gate, - mag_var, 0, 0); + velocity_variance, pos_horiz_variance, pos_vert_variance, + mag_var, terrain_alt_variance, airspeed_variance); + +} + +bool AP_ExternalAHRS_MicroStrain7::times_healthy() const +{ + uint32_t now = AP_HAL::millis(); + + // Expect the following rates: + // * Navigation Filter: 25Hz = 40mS + // * GPS: 2Hz = 500mS + // * IMU: 25Hz = 40mS + + // Allow for some slight variance of 10% + constexpr float RateFoS = 1.1; + + constexpr uint32_t expected_filter_time_delta_ms = 40; + constexpr uint32_t expected_gps_time_delta_ms = 500; + constexpr uint32_t expected_imu_time_delta_ms = 40; + + const bool times_healthy = (now - last_imu_pkt < expected_imu_time_delta_ms * RateFoS && \ + now - last_gps_pkt < expected_gps_time_delta_ms * RateFoS && \ + now - last_filter_pkt < expected_filter_time_delta_ms * RateFoS); + + return times_healthy; +} +bool AP_ExternalAHRS_MicroStrain7::filter_healthy() const +{ + const auto filter_state = static_cast(filter_status.state); + const bool filter_healthy = filter_state_healthy(filter_state); + return filter_healthy; } bool AP_ExternalAHRS_MicroStrain7::filter_state_healthy(FilterState state) @@ -378,7 +418,6 @@ bool AP_ExternalAHRS_MicroStrain7::filter_state_healthy(FilterState state) default: return false; } - // return state == FilterState::GQ7_FULL_NAV || state == FilterState::GQ7_AHRS; } #endif // AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h index d9e0832272715..5cff5af56a6dc 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h @@ -74,6 +74,13 @@ class AP_ExternalAHRS_MicroStrain7: public AP_ExternalAHRS_backend, public AP_Mi void post_filter() const; void update_thread(); + void check_initialise_state(); + + // Returns true when data is not stale. + bool times_healthy() const; + + // Returns true when the filter is currently healthy. + bool filter_healthy() const; // Only some of the fix types satisfy a healthy filter. // GQ7_VERT_GYRO is NOT considered healthy for now. @@ -83,6 +90,9 @@ class AP_ExternalAHRS_MicroStrain7: public AP_ExternalAHRS_backend, public AP_Mi AP_HAL::UARTDriver *uart; HAL_Semaphore sem; + // Used to monitor initialization state. + bool last_init_state = false; + }; #endif // AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED diff --git a/libraries/AP_ExternalAHRS/MicroStrain_common.cpp b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp index 7ced1123aa1d2..f6cfa02008cf9 100644 --- a/libraries/AP_ExternalAHRS/MicroStrain_common.cpp +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp @@ -60,6 +60,10 @@ enum class FilterPacketField { NED_VELOCITY = 0x02, // https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/filter_data/data/mip_field_filter_attitude_quaternion.htm ATTITUDE_QUAT = 0x03, + // https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x08.htm + LLH_POSITION_UNCERTAINTY = 0x08, + // https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/0x82/data/0x09.htm + NED_VELOCITY_UNCERTAINTY = 0x09, // https://s3.amazonaws.com/files.microstrain.com/GQ7+User+Manual/external_content/dcp/Data/shared_data/data/mip_field_shared_gps_timestamp.htm GPS_TIMESTAMP = 0xD3, }; @@ -295,6 +299,28 @@ void AP_MicroStrain::handle_filter(const MicroStrain_Packet &packet) filter_data.attitude_quat.normalize(); break; } + case FilterPacketField::LLH_POSITION_UNCERTAINTY: { + const float north_pos_acc = be32tofloat_ptr(packet.payload, i+2); + const float east_pos_acc = be32tofloat_ptr(packet.payload, i+6); + const float down_pos_acc = be32tofloat_ptr(packet.payload, i+10); + filter_data.ned_position_uncertainty = Vector3f( + north_pos_acc, + east_pos_acc, + down_pos_acc + ); + break; + } + case FilterPacketField::NED_VELOCITY_UNCERTAINTY: { + const float north_vel_uncertainty = be32tofloat_ptr(packet.payload, i+2); + const float east_vel_uncertainty = be32tofloat_ptr(packet.payload, i+6); + const float down_vel_uncertainty = be32tofloat_ptr(packet.payload, i+10); + filter_data.ned_velocity_uncertainty = Vector3f( + north_vel_uncertainty, + east_vel_uncertainty, + down_vel_uncertainty + ); + break; + } case FilterPacketField::FILTER_STATUS: { filter_status.state = be16toh_ptr(&packet.payload[i+2]); filter_status.mode = be16toh_ptr(&packet.payload[i+4]); diff --git a/libraries/AP_ExternalAHRS/MicroStrain_common.h b/libraries/AP_ExternalAHRS/MicroStrain_common.h index 9792a4f2ca1ce..0e6b35db20ac6 100644 --- a/libraries/AP_ExternalAHRS/MicroStrain_common.h +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.h @@ -77,15 +77,16 @@ class AP_MicroStrain struct { uint16_t week; uint32_t tow_ms; - float horizontal_position_accuracy; - float vertical_position_accuracy; + // 1-sigma position uncertainty in the NED local-level frame [meters]. + Vector3f ned_position_uncertainty; int32_t lon; int32_t lat; int32_t hae_altitude; float ned_velocity_north; float ned_velocity_east; float ned_velocity_down; - float speed_accuracy; + // 1-sigma velocity uncertainties in the NED local-level frame. + Vector3f ned_velocity_uncertainty; // 4x1 vector representation of the quaternion describing the orientation of the device with respect to the NED local-level frame. // NED [Qw, Qx, Qy, Qz] Quaternion attitude_quat; diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index c4de0473a96f6..456cab154c6f6 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -406,7 +406,7 @@ class AP_HAL::RCOutput { // See WS2812B spec for expected pulse widths static constexpr uint32_t NEOP_BIT_WIDTH_TICKS = 8; - static constexpr uint32_t NEOP_BIT_0_TICKS = 3; + static constexpr uint32_t NEOP_BIT_0_TICKS = 2; static constexpr uint32_t NEOP_BIT_1_TICKS = 6; // neopixel does not use pulse widths at all static constexpr uint32_t PROFI_BIT_0_TICKS = 7; diff --git a/libraries/AP_HAL/utility/sparse-endian.h b/libraries/AP_HAL/utility/sparse-endian.h index ee594fe8ea071..f562e1166dca0 100644 --- a/libraries/AP_HAL/utility/sparse-endian.h +++ b/libraries/AP_HAL/utility/sparse-endian.h @@ -102,8 +102,8 @@ static inline uint64_t be64toh_ptr(const uint8_t *p) { return (uint64_t) p[7] | static inline float be32tofloat_ptr(const uint8_t *p) { return int32_to_float_le(be32toh_ptr(p)); } static inline float be32tofloat_ptr(const uint8_t *p, const uint8_t offset) { return be32tofloat_ptr(&p[offset]); } #ifdef ALLOW_DOUBLE_MATH_FUNCTIONS -static inline float be64todouble_ptr(const uint8_t *p) { return uint64_to_double_le(be64toh_ptr(p)); } -static inline float be64todouble_ptr(const uint8_t *p, const uint8_t offset) { return be64todouble_ptr(&p[offset]); } +static inline double be64todouble_ptr(const uint8_t *p) { return uint64_to_double_le(be64toh_ptr(p)); } +static inline double be64todouble_ptr(const uint8_t *p, const uint8_t offset) { return be64todouble_ptr(&p[offset]); } #endif static inline void put_le16_ptr(uint8_t *p, uint16_t v) { p[0] = (v&0xFF); p[1] = (v>>8); } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/README.md new file mode 100644 index 0000000000000..94cffb226d0e5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/README.md @@ -0,0 +1,92 @@ +# iFlight BLITZ F745 Flight Controller + +https://shop.iflight.com/electronics-cat27/BLITZ-F745-Flight-Controller-Pro2141 + +The BLITZ F745 is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU: BGA-STM32F745, 216MHz + - Gyro: ICM42688 + - 32Mbytes Onboard Flash + - BEC output: 5V 2.5A + - Barometer: DPS310 + - OSD: AT7456E + - 6 UARTS: (UART1, UART2, UART3, UART4, UART5, UART6) + - I2C for external compass. + - 9 PWM outputs (8 motor outputs and 1 LED output) + +## Pinout + +![BLITZ F745 Board](blitz_f7_pinout.jpg "BLITZ F745") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|UART1 (DJI connector)| +|SERIAL2|TX2/RX2|UART2 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (GPS, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4| +|SERIAL5|TX5/RX5|UART5| +|SERIAL6|RX6|UART6 (ESC telemetry)| + +Note:UART3 is used for GPS not UART4 as shown in typical wiring diagram + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX). It supports all serial RC protocols. + +## OSD Support + +The BLITZ F745 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BLITZ F745 has 9 PWM outputs. The pads for motor output are M1 to M8 on the board and M1-M4 are also in the ESC connector housing. All 9 outputs support DShot and the first four outputs support bi-directional DShot as well as all PWM types. Output 9 is the "LED" pin and is configured for serial LED by default. + +The PWM are in three groups: + + - PWM 1-4 in group1 + - PWM 5-8 in group2 + - PWM 9 in group3 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 12 + - BATT_VOLT_MULT 11 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ F745 does not have a builtin compass, but you can attach an external compass to I2C pins. + +## NeoPixel LED + +The board includes a NeoPixel LED on the underside which is pre-configured to output ArduPilot sequences. This is the fifth PWM output. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/blitz_f7_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/blitz_f7_pinout.jpg new file mode 100644 index 0000000000000..1867bf29e456b Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/blitz_f7_pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/defaults.parm new file mode 100644 index 0000000000000..558c392df4926 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 +OSD_TYPE2 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef-bl.dat new file mode 100644 index 0000000000000..4b0c876789c24 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef-bl.dat @@ -0,0 +1,43 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_F7_AIO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzF7 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 96 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# Chip select pins +PA15 FLASH1_CS CS +PE4 OSD1_CS CS +PA4 GYRO1_CS CS + +PC9 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef.dat new file mode 100644 index 0000000000000..88ddc95821e85 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzF745/hwdef.dat @@ -0,0 +1,163 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_F7_AIO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F7xx STM32F745xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzF7 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 96 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 5 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PD6 SPI3_MOSI SPI3 + +# SPI4 +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# Chip select pins +PA15 FLASH1_CS CS +PE4 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PD3 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 - VTX +PA10 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort + +# USART2 - RX +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 - GPS +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS + +# UART4 +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None + +# UART5 +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None + +# USART6 - ESC Telem +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry + +# I2C ports +I2C_ORDER I2C1 I2C4 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C4 +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# Servos + +# ADC ports + +# ADC1 +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_CURR_SCALE 50.0 +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_VOLT_SCALE 11.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 15 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB4 TIM3_CH1 TIM3 PWM(1) GPIO(50) BIDIR # M1 +PB0 TIM3_CH3 TIM3 PWM(2) GPIO(51) # M2 +PB5 TIM3_CH2 TIM3 PWM(3) GPIO(52) # M3 +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR # M4 +PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5 +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) # M6 +PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56) # M7 +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) # M8 + +# LEDs +PC9 TIM8_CH4 TIM8 PWM(9) GPIO(58) # M9 + +PD15 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +# Dataflash setup +SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ + +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI4 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# IMU setup + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +DMA_NOSHARE TIM3_UP TIM1_UP SPI1* +DMA_PRIORITY TIM3_UP TIM1_UP SPI1* + +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180 + +# Barometer setup +BARO DPS310 I2C:1:0x76 + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# save some flash +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/README.md new file mode 100644 index 0000000000000..64c4321d822f9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/README.md @@ -0,0 +1,113 @@ +# iFlight BLITZ H7 Pro Flight Controller + +The Blitz H7 Pro is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - Gyro: ICM42688 + - 32Gb SDCard for logging + - BEC output: 5V 2.5A, switch controlled 12v 2A + - Barometer: DPS310 + - OSD: AT7456E + - 7x UARTs + - 13x PWM Outputs (12 Motor Output, 1 LED) + - Battery input voltage: 2S-8S + - 2x I2C for external compass, airspeed, etc. + - CAN port + +## Pinout + +![BLITZ H7 Pro Board](blitz_h7_pro.png "BLITZ H7 Pro") + +back side pinout image pending from iFlight + +The expansion connector provides access to the following pins: + - CAN+/CAN- + - M9 through M12 + - TX7/RX7 + - SCL2/SDA2 + - RSSI + - 5V/12V/GND + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|UART1 (DJI connector, DMA-enabled)| +|SERIAL2|TX2/RX2|UART2 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (GPS, DMA-enabled)| +|SERIAL5|RX5|UART5 (ESC Telemetry)| +|SERIAL6|TX6/RX6|UART6| +|SERIAL7|TX7/RX7|UART7| + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX) pins which forms part of the DJI connector. It supports all serial RC protocols. + +## OSD Support + +The BLITZ H7 Pro supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BLITZ H7 Pro has 13 PWM outputs. The pads for motor output M1-M4 are in one ESC connector and M5-M8 in the second ESC connector. The remaining outputs are on the pads on the daughterboard. The first 8 outputs support bi-directional DShot and DShot, as well as all PWM types. Outputs 9-10 support DShot, as well as all PWM types and outputs 11-12 only support PWM. + +The PWM are in in five groups: + + - PWM 1-2 in group1 + - PWM 3-6 in group2 + - PWM 7-10 in group3 + - PWM 11-12 in group4 + - PWM 13 in group5 +.. note:: for users migrating from BetaflightX quads, the first four outputs M1-M4 have been configured for use with existing motor wiring using these default parameters: + +- :ref:`FRAME_CLASS` = 1 (Quad) +- :ref:`FRAME_TYPE` = 12 (BetaFlightX) + + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +Video Power Control +================ + +The 12V video power can be turned off/on using GPIO 81 which is already assigned by default to RELAY2. This relay can be controlled either from the GCS or using a transmitter channel (See :ref:`common-auxiliary-functions`) +RSSI +==== + +Analog RSSI pin is "4" + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_VOLT_MULT 11 + - BATT_CURR_PIN 11 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ H7 Pro does not have a builtin compass, but you can attach an external compass to I2C pins. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/blitz_h7_pro.png b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/blitz_h7_pro.png new file mode 100644 index 0000000000000..b1a6e0e177efc Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/blitz_h7_pro.png differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm new file mode 100644 index 0000000000000..362a17f38f9a9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm @@ -0,0 +1,3 @@ +# setup for LEDs on chan9 +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef-bl.dat new file mode 100644 index 0000000000000..22afd74789dbf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef-bl.dat @@ -0,0 +1,45 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_H7_PRO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzH7Pro + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 2048 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 384 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# Chip select pins +PB12 OSD1_CS CS +PC15 GYRO1_CS CS +PE11 GYRO2_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 + +PD10 VTX_PWR OUTPUT GPIO(81) HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef.dat new file mode 100644 index 0000000000000..966e60c17c65c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/hwdef.dat @@ -0,0 +1,184 @@ + +# hw definition file for processing by chibios_hwdef.py +# for IFLIGHT_BLITZ_H7_PRO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_BlitzH7Pro + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +MCU_CLOCKRATE_MHZ 480 + +FLASH_SIZE_KB 2048 + +FLASH_RESERVE_START_KB 384 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# Chip select pins +PB12 OSD1_CS CS +PC15 GYRO1_CS CS +PE11 GYRO2_CS CS + +# Beeper +PA15 TIM2_CH1 TIM2 GPIO(32) ALARM + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 UART8 OTG2 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 - VTX +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort + +# USART2 - RX +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 - GPS +PB8 UART4_RX UART4 +PB9 UART4_TX UART4 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_GPS + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry + +# UART7 +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +# Not pinned out +PE9 UART7_RTS UART7 +PE10 UART7_CTS UART7 + +# UART8 +PE0 UART8_RX UART8 NODMA +PE1 UART8_TX UART8 NODMA + +# I2C ports +I2C_ORDER I2C1 I2C2 +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +define HAL_OS_FATFS_IO 1 + +# CAN +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# VTX power +PD10 VTX_PWR OUTPUT GPIO(81) HIGH +define RELAY2_PIN_DEFAULT 81 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 50.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 8 +define HAL_BATT_MONITOR_DEFAULT 4 +PC4 PRESSURE_SENS ADC1 SCALE(2) +define HAL_DEFAULT_AIRSPEED_PIN 4 + +# MOTORS +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2 +PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52) BIDIR # M3 +PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53) # M4 +PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR # M5 +PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) # M6 +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR # M7 +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) # M8 +# Motor outputs on daughterboard +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) # M9 +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) # M10 +PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA # M11 +PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA # M12 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # M9 + +PE3 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +PE4 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_B_LED_PIN 91 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# Barometer setup +BARO DPS310 I2C:1:0x76 + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ + +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180 + +DMA_NOSHARE TIM3_UP TIM5_UP TIM4_UP SPI1* +DMA_PRIORITY TIM3_UP TIM5_UP TIM4_UP SPI1* + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 1 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/README.md new file mode 100644 index 0000000000000..e44dd4a6d2915 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/README.md @@ -0,0 +1,89 @@ +# iFlight BLITZ Mini F745 Flight Controller + +https://shop.iflight.com/BLITZ-Mini-F745-Flight-Controller-Pro2142 + +The BLITZ Mini F745 is a flight controller produced by [iFlight](https://shop.iflight-rc.com/). + +## Features + + - MCU: BGA-STM32F745, 216MHz + - Gyro: ICM42688 + - 16Mbytes Onboard Flash + - BEC output: 5V 2.5A + - Barometer: DPS310 + - OSD: AT7456E + - 6 UARTS: (UART1, UART2, UART3, UART4, UART5, UART6) + - I2C for external compass. + - 5 PWM outputs (4 motor outputs and 1 LED output) + +## Pinout + +![BLITZ Mini F745 Board](blitz_f7_pinout.jpg "BLITZ Mini F745") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|UART1 (DJI connector)| +|SERIAL2|TX2/RX2|UART2 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (GPS, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4| +|SERIAL5|TX5/RX5|UART5| +|SERIAL6|RX6|UART6 (ESC telemetry)| + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX). It supports all serial RC protocols. + +## OSD Support + +The BLITZ Mini F745 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BLITZ Mini F745 has 5 PWM outputs. The motor outputs M1-M4 are in the ESC connector housing. All 5 outputs support DShot and the first four outputs support bi-directional DShot as well as all PWM types. Output 5 is the "LED" pin and is configured for serial LED by default. + +The PWM are in two groups: + + - PWM 1-4 in group1 + - PWM 5 in group2 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current sensor. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 12 + - BATT_VOLT_MULT 11 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ Mini F745 does not have a builtin compass, but you can attach an external compass to I2C pins. + +## NeoPixel LED + +The board includes a NeoPixel LED on the underside which is pre-configured to output ArduPilot sequences. This is the fifth PWM output. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/blitz_f7_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/blitz_f7_pinout.jpg new file mode 100644 index 0000000000000..5bfb22ea69275 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/blitz_f7_pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/defaults.parm new file mode 100644 index 0000000000000..5adf224c99384 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan5 +SERVO5_FUNCTION 120 +NTF_LED_TYPES 257 +OSD_TYPE2 5 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef-bl.dat new file mode 100644 index 0000000000000..5b31b8c20b51d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef-bl.dat @@ -0,0 +1,4 @@ + +include ../BlitzF745/hwdef-bl.dat + +APJ_BOARD_ID AP_HW_BlitzF7Mini diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef.dat new file mode 100644 index 0000000000000..300a026dde982 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzMiniF745/hwdef.dat @@ -0,0 +1,11 @@ +include ../BlitzF745/hwdef.dat + +APJ_BOARD_ID AP_HW_BlitzF7Mini + +undef IMU +undef PE9 PE11 PE13 PE14 PC9 + +IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_135 + +# LEDs +PC9 TIM8_CH4 TIM8 PWM(5) GPIO(54) # M5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/README.md new file mode 100644 index 0000000000000..37dfb7934484e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/README.md @@ -0,0 +1,106 @@ +# iFlight BLITZ Wing H743 Flight Controller + +The BLITZ Wing H743 is a flight controller produced by [iFlight](https://shop.iflight.com/electronics-cat27/BLITZ-Wing-H743-Flight-Controller-Pro2174). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - Gyro: ICM42688 + - SDCard for logging + - 5V 3A BEC for Flight Controller + - 9V 3A BEC for VTX + - 5-8.4V 6A BEC for Servo + - Barometer: DPS310 + - OSD: AT7456E + - 7x UARTs + - 13x PWM Outputs (12 Motor Output, 1 LED) + - Battery input voltage: 2S-8S + - 2x I2C for external compass, airspeed, etc. + - CAN port + +## Physical + - Mount pattern: 30.5*30.5mm/?4 + - Dimensions: 36.9*52mm + - Weight: 35g + +## Pinout + +![BLITZ Wing H743 Board](blitz_h7_wing_top.PNG "BLITZ Wing H743 Top") +![BLITZ Wing H743 Board](blitz_h7_wing_middle.PNG "BLITZ Wing H743 Middle") +![BLITZ Wing H743 Board](blitz_h7_wing_bottom.PNG "BLITZ Wing H743 Bottom") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|UART1 (DJI connector, DMA-enabled)| +|SERIAL2|TX2/RX2|UART2 (RX, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (GPS, DMA-enabled)| +|SERIAL6|TX6/RX6|UART6| +|SERIAL7|TX7/RX7|UART7| +|SERIAL8|TX8/RX8|UART8 (ESC Telemetry)| + +## RC Input + +RC input is configured on the (UART2_RX/UART2_TX) pins which forms part of the DJI connector. It supports all serial RC protocols. + +## OSD Support + +The BLITZ Wing H743 supports OSD using OSD_TYPE 1 (MAX7456 driver). Simultaneously, DisplayPort HD OSD is enabled by default and available on the HD VTX connector. + +## PWM Output + +The BLITZ Wing H743 has 13 PWM outputs. The first 8 outputs support bi-directional DShot and DShot, as well as all PWM types. Outputs 9-10 support DShot, as well as all PWM types and outputs 11-12 only support PWM. + +The PWM are in in five groups: + + - PWM 1-2 in group1 + - PWM 3-6 in group2 + - PWM 7-10 in group3 + - PWM 11-12 in group4 + - PWM 13 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Video Power Control + +The 9V video power can be turned off/on using GPIO 81 which is already assigned by default to RELAY2. This relay can be controlled either from the GCS or using a transmitter channel (See :ref:`common-auxiliary-functions`) + +## Analog Airspeed Input + +The analog airspeed pin is "4" + +## Battery Monitoring + +The board has a built-in voltage sensor and current sensor. The voltage sensor can handle up to 8S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_VOLT_MULT 11 + - BATT_CURR_PIN 11 + - BATT_CURR_MULT 50 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The BLITZ Wing H743 does not have a builtin compass, but you can attach an external compass to I2C pins. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_bottom.PNG b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_bottom.PNG new file mode 100644 index 0000000000000..9de0830011dd3 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_bottom.PNG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_middle.PNG b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_middle.PNG new file mode 100644 index 0000000000000..1aad2f38886b8 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_middle.PNG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_top.PNG b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_top.PNG new file mode 100644 index 0000000000000..6ec7202d6ae38 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/blitz_h7_wing_top.PNG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/defaults.parm new file mode 100644 index 0000000000000..5d4fab1adaed4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/defaults.parm @@ -0,0 +1,4 @@ +# setup for LEDs on chan9 +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 +OSD_TYPE2 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef-bl.dat new file mode 100644 index 0000000000000..2406ec403c5e7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../BlitzH743Pro/hwdef-bl.dat + +APJ_BOARD_ID AP_HW_BlitzH7Wing \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef.dat new file mode 100644 index 0000000000000..2332cd2e02803 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzWingH743/hwdef.dat @@ -0,0 +1,13 @@ +include ../BlitzH743Pro/hwdef.dat + +APJ_BOARD_ID AP_HW_BlitzH7Wing + +undef SERIAL_ORDER +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8 OTG2 + +undef DEFAULT_SERIAL5_PROTOCOL +define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry +undef HAL_FRAME_TYPE_DEFAULT + +undef PC5 +undef BOARD_RSSI_ANA_PIN diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat index fd84470fedae8..ea57d173ea53e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat @@ -105,9 +105,7 @@ define HAL_I2C_INTERNAL_MASK 1 # enable pins PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold +# start peripheral power on PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH PG4 VDD_5V_PERIPH_EN OUTPUT HIGH @@ -230,7 +228,7 @@ SPIDEV bmi088_g SPI4 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ SPIDEV ms5611_imu SPI4 DEVID1 MS5611_IMU_CS MODE3 20*MHZ 20*MHZ SPIDEV ms5611_board SPI6 DEVID1 MS5611_BOARD_CS MODE3 20*MHZ 20*MHZ SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ -SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 1*MHZ 1*MHZ #Mount icm20649 or icm20689 on SPI6 SPIDEV icm20649 SPI6 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat index fa8020580bd1c..b01fc9d2a177f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat @@ -105,9 +105,7 @@ define HAL_I2C_INTERNAL_MASK 1 # enable pins PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold +# start peripheral power on PD11 VDD_5V_HIPOWER_EN OUTPUT HIGH PG4 VDD_5V_PERIPH_EN OUTPUT HIGH @@ -243,8 +241,8 @@ SPIDEV icm42688 SPI4 DEVID2 ICM42688_CS MODE3 2*MHZ 8*MHZ # RM3100 may be on SPI1 or SPI2 (not both). Later board revisions # have the RM3100 on SPI2, to leave SPI1 free for ADIS1647x -SPIDEV rm3100-1 SPI1 DEVID1 RM3100_CS MODE3 2*MHZ 8*MHZ -SPIDEV rm3100-2 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100-1 SPI1 DEVID1 RM3100_CS MODE3 1*MHZ 1*MHZ +SPIDEV rm3100-2 SPI2 DEVID2 RM3100_CS MODE3 1*MHZ 1*MHZ # two baro BARO MS56XX SPI:ms5611_imu diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat index 95690d23169b2..736fe23f512ca 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat @@ -109,7 +109,7 @@ SPIDEV icm42688_0 SPI1 DEVID1 ICM42688_0_CS MODE3 2*MHZ 8*MHZ SPIDEV ms5611_0 SPI1 DEVID2 BARO_0_CS MODE3 20*MHZ 20*MHZ SPIDEV icm42688_1 SPI2 DEVID1 ICM42688_1_CS MODE3 2*MHZ 8*MHZ -SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI2 DEVID2 RM3100_CS MODE3 1*MHZ 1*MHZ SPIDEV icm20649 SPI4 DEVID1 ICM20649_CS MODE3 4*MHZ 8*MHZ SPIDEV ms5611_1 SPI4 DEVID2 BARO_1_CS MODE3 20*MHZ 20*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat index 024572edf2ee6..778cb545a6421 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat @@ -109,11 +109,9 @@ define HAL_I2C_INTERNAL_MASK 1 # enable pins PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold -PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW PG5 VDD_5V_RC_EN OUTPUT HIGH PG6 VDD_5V_WIFI_EN OUTPUT HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat index 9d27f7e12ed89..d1b31466d5bae 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonF427/hwdef.dat @@ -92,7 +92,7 @@ PB5 SPI3_MOSI SPI3 SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20649 SPI1 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ SPIDEV icm42605 SPI1 DEVID3 ICM42605_CS MODE3 2*MHZ 8*MHZ -SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 1*MHZ 1*MHZ SPIDEV osd SPI1 DEVID5 MAX7456_CS MODE0 10*MHZ 10*MHZ SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat index 36bed89636909..af07892834452 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlyingMoonH743/hwdef.dat @@ -99,7 +99,7 @@ PB5 SPI3_MOSI SPI3 SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ SPIDEV icm20649 SPI1 DEVID2 ICM20649_CS MODE3 2*MHZ 8*MHZ SPIDEV icm42605 SPI1 DEVID3 ICM42605_CS MODE3 2*MHZ 8*MHZ -SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI1 DEVID4 RM3100_CS MODE3 1*MHZ 1*MHZ SPIDEV osd SPI1 DEVID5 MAX7456_CS MODE0 10*MHZ 10*MHZ SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/FoxeerF405v2.jpg b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/FoxeerF405v2.jpg new file mode 100644 index 0000000000000..a0b4bcce0f63a Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/FoxeerF405v2.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md new file mode 100644 index 0000000000000..b8760ff715db5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/README.md @@ -0,0 +1,98 @@ +# FoxeerF405v2 Flight Controller + +The FoxeerF405v2 is a flight controller produced by [Foxeer](https://www.foxeer.com/). + +## Features + + - MCU - STM32F405 32-bit processor + - IMU - ICM42688 + - Barometer - DPS310 + - OSD - AT7456E + - Onboard Flash: 128Mbit + - 6x UARTs + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 2S-8S + - BEC 3.3V 0.5A + - BEC 5V 2A + - BEC 10V 2A + +## Pinout + +![FoxeerF405v2 Board](FoxeerF405v2.jpg "FoxeerF405v2") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (ESC Telemetry) + - SERIAL2 -> UART2 (RX, DMA-enabled) + - SERIAL3 -> UART3 (VTX Tramp) + - SERIAL4 -> UART4 (MSP DisplayPort, DMA-enabled) + - SERIAL5 -> UART5 (GPS, DMA-enabled) + - SERIAL6 -> UART6 (RX in DJI connector) + +## RC Input + +RC input is configured by default on the R2 (UART2_RX) pad. It supports all serial RC +protocols. Half-duplex serial protocols should be configured on T2 (UART2_TX). RC input is also +supported on UART6_RX within the DJI connector, although because it is not inverted it cannot be +used for SBUS. + +## OSD Support + +The FoxeerF405v2 supports OSD using OSD_TYPE 1 (MAX7456 driver) or OSD_TYPE 3 if using DJI OSD + +## PWM Output + +The FoxeerF405v2 supports up to 9 PWM outputs. The pads for motor output +M1 to M8 are provided on both the motor connectors and on separate pads, plus +M9 on a separate pad for LED strip or another PWM output. + +The PWM is in 4 groups: + + - PWM 1,4 in group1 + - PWM 2,3 in group2 + - PWM 5,9 in group3 + - PWM 6-8 in group4 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Note that channel 9 is explicitly configured as NeoPixel output +which means that channel 5 cannot be used as a motor output without disabling NeoPixel +support on channel 9. + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 8S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11 + - BATT_AMP_PERVLT 142.9 + +## Compass + +The FoxeerF405v2 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Control GPIO pins +GPIO pin 71 can be used to control camera switching. It is configured +by default on relay 3 and so you can associate an RC switch with relay 3 in order +to switch camera outputs. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/defaults.parm new file mode 100644 index 0000000000000..9b8696da0c64b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/defaults.parm @@ -0,0 +1,5 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +NTF_LED_TYPES 257 + +GPS_DRV_OPTIONS 4 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat new file mode 100644 index 0000000000000..fc17a788636d5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef-bl.dat @@ -0,0 +1,40 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FOXEERF405V2 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_FOXEERF405_V2 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 48 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# Chip select pins +PB12 FLASH1_CS CS +PC14 OSD1_CS CS +PA4 GYRO1_CS CS + +PA13 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat new file mode 100644 index 0000000000000..31b8c0a884528 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat @@ -0,0 +1,166 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FOXEERF405V2 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +HAL_CHIBIOS_ARCH_F405 1 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_FOXEERF405_V2 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 48 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 5 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +# SPI3 +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# Chip select pins +PB12 FLASH1_CS CS +PC14 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PC15 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_ESCTelemetry + +# USART2 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Tramp + +# UART4 +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MSP_DisplayPort + +# UART5 +PC12 UART5_TX UART5 NODMA +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA + +# I2C ports +I2C_ORDER I2C1 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# Servos +PB1 SERVO1 OUTPUT GPIO(70) LOW +define RELAY2_PIN_DEFAULT 70 +PB14 CAMERA1 OUTPUT GPIO(71) LOW +define RELAY3_PIN_DEFAULT 71 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 142.9 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 15 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) # M1 +PC9 TIM8_CH4 TIM8 PWM(2) GPIO(51) # M2 +PC8 TIM8_CH3 TIM8 PWM(3) GPIO(52) # M3 +PB15 TIM1_CH3N TIM1 PWM(4) GPIO(53) # M4 +PB6 TIM4_CH1 TIM4 PWM(5) GPIO(54) # M5 +PA15 TIM2_CH1 TIM2 PWM(6) GPIO(55) # M6 +PB11 TIM2_CH4 TIM2 PWM(7) GPIO(56) # M7 +PB10 TIM2_CH3 TIM2 PWM(8) GPIO(57) # M8 + +PB7 TIM4_CH2 TIM4 PWM(9) GPIO(58) # LED + +# LEDs + +PA13 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 + +PA14 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_B_LED_PIN 91 +define HAL_GPIO_LED_ON 0 + +# Dataflash setup +SPIDEV dataflash SPI2 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ + +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI3 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# Barometer setup +BARO DPS310 I2C:0:0x76 + +# IMU setup + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ + +IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_90 + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat index 239686e80caae..d3cd8ab2b5bf3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat @@ -102,17 +102,18 @@ define HAL_GPIO_LED_OFF 1 PA9 USART1_TX USART1 PA10 USART1_RX USART1 -# USART2 -PD5 USART2_TX USART2 NODMA -PD6 USART2_RX USART2 NODMA +# USART2 (GPS) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_GPS # USART3 (VTX) PD8 USART3_TX USART3 NODMA PD9 USART3_RX USART3 NODMA -# UART4 (GPS) -PD1 UART4_TX UART4 -PD0 UART4_RX UART4 +# UART4 (WiFi) +PD1 UART4_TX UART4 NODMA +PD0 UART4_RX UART4 NODMA # UART5 (SPORT) PC12 UART5_TX UART5 NODMA diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat index 5b9a535f5ef22..82db60d63e53c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef-bl.dat @@ -70,9 +70,9 @@ PD9 USART3_RX USART3 NODMA # armed indication PC12 nARMED OUTPUT HIGH -# start peripheral power off -PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # LEDs PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat index 0be4c176b5f2f..bc0651cf2a7cd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat @@ -214,11 +214,9 @@ PD15 VDD_3V3_SENSORS2_EN OUTPUT HIGH PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold -PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # Control of Spektrum power pin PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat index da0f10b992803..e80be6d00203b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef-bl.dat @@ -59,9 +59,9 @@ PD2 UART5_RX UART5 PD8 USART3_TX USART3 PD9 USART3_RX USART3 -# start peripheral power off -PC10 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PE2 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PC10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PE2 nVDD_5V_PERIPH_EN OUTPUT LOW # LEDs PD10 LED_ACTIVITY OUTPUT OPENDRAIN GPIO(90) HIGH # red diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat index 4677c93b2ab37..7872fc8e50a10 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -164,11 +164,9 @@ define HAL_IMUHEAT_I_DEFAULT 0.07 # power enable pins PB2 VDD_3V3_SENSORS1_EN OUTPUT HIGH -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold -PC10 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PE2 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PC10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PE2 nVDD_5V_PERIPH_EN OUTPUT LOW # Control of Spektrum power pin PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat index 8ca7a6488f8d6..a8da5509565d1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef-bl.dat @@ -60,9 +60,9 @@ PD9 USART3_RX USART3 # armed indication PE6 nARMED OUTPUT HIGH -# start peripheral power off -PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PF12 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # LEDs PE3 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # red diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat index 1cf5be3a9f743..a53e62d65d4bd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat @@ -227,11 +227,9 @@ PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH -# start peripheral power off, then enable after init -# this prevents a problem with radios that use RTS for -# bootloader hold -PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH -PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +# start peripheral power on +PG10 nVDD_5V_HIPOWER_EN OUTPUT LOW +PG4 nVDD_5V_PERIPH_EN OUTPUT LOW # Control of Spektrum power pin PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(73) @@ -357,6 +355,7 @@ IMU Invensensev3 SPI:icm45686-2 ROTATION_ROLL_180 BOARD_MATCH(FMUV6_BOARD_HOLY IMU Invensensev3 SPI:icm45686-3 ROTATION_ROLL_180 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_45686) IMU Invensensev3 SPI:icm45686-1 ROTATION_YAW_90 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_45686) +define HAL_INS_HIGHRES_SAMPLE 7 define HAL_DEFAULT_INS_FAST_SAMPLE 7 # enable RAMTROM parameter storage diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/H7V1_0502.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/H7V1_0502.jpg new file mode 100644 index 0000000000000..4e47709703266 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/H7V1_0502.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/README.md new file mode 100644 index 0000000000000..14432f238aebf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/README.md @@ -0,0 +1,116 @@ +# SDMODEL SDH7 V2 Flight Controller + +## Features + + - STM32H743 microcontroller + - MPU6000 IMU + - BMP280 barometer + - IST8310 Compass + - microSD card slot + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![SDH7V2](SDMODEL_H7V2.png) + +![SDH7V2](H7V1_0502.png) + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (Telem1) (MSP DisplayPort)(DMA Capable) + - SERIAL2 -> UART2 (Telem2) (connected to internal BT module, not useable by ArduPilot) + - SERIAL3 -> UART3 (GPS)(DMA Capable) + - SERIAL4 -> UART4 (GPS) + - SERIAL5 -> not available + - SERIAL6 -> UART6 (RX6 in RCinput, ALT config to use as UART input) + - SERIAL7 -> UART7 RX pin only, ESC telem)(DMA Capable) + +## RC Input + +RC input is configured on the R6 (UART6_RX) pin. It supports all single wire unidirectional RC +protocols. For protocols requiring half-duplex or full duplex serial for operation +select another UART with DMA and set its protocol to "23". To use this UART for other uses, set +:ref:`BRD_ALT_CONFIG` to "1" + +## FrSky Telemetry + +FrSky Telemetry is supported using the Tx pin of any UART including SERIAL6/UART6 . You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL6). Note this assumes the RC input is using default (ALT_BRD_CONFIG =0). Obviously, if using ALT_BRD_CONFIG = 1 for full duplex RC prtocols, you must a different UART for FrSky Telemetry. + + - SERIAL6_PROTOCOL 10 + - SERIAL6_OPTIONS 7 + +## OSD Support + +The SDMODEL SDH7 V2 supports OSD using OSD_TYPE 1 (MAX7456 driver).The defaults are also setup to allow DJI Goggle OSD support on UART1. Both OSDs can operate simultaneously. + +## VTX Support + +The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect +this to a peripheral requiring 5v. The 9v supply is controlled by RELAY_PIN2 set to GPIO 81 and is on by default. It can be configured to be operated by an RC switch by selecting the function RELAY2. + +## Camera Control + +The Cam pin is GPIO82 and is set to be controlled by RELAY4 by default. Relay pins can be controlled either by an RC switch or GCS command. See :ref:`common-relay` for more information. + +## PWM Output + +The SDMODEL SDH7 V2 supports up to 9 PWM or DShot outputs. Outputs 1-4 support BDShot. The pads for motor output +M1 to M8 on the two motor connectors, plus M9 preconfigured for LED strip or can be used as another +PWM output. + +The PWM is in 5 groups: + + - PWM 1, 2 in group1 + - PWM 3, 4 in group2 + - PWM 5, 6 in group3 + - PWM 7, 8 in group4 + - PWM 9 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +.. note:: for users migrating from BetaflightX quads, the first four outputs M1-M4 have been configured for use with existing motor wiring using these default parameters: + +- :ref:`FRAME_CLASS` = 1 (Quad) +- :ref:`FRAME_TYPE` = 12 (BetaFlightX) + +## Battery Monitoring + +The board has a builting voltage and current sensor. The current +sensor can read up to 130 Amps. The voltage sensor can handle up to 6S +LiPo batteries. + +The correct battery setting parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11 + - BATT_AMP_PERVLT 59.5 + +## Compass + +SDMODEL SDH7 V2 has a built-in compass IST8310, but you can add an external compass 2nd using the I2C connections on the SDA and SCL pads. + +## Firmware + +Firmware for these boards can be found `here `_ in sub-folders labeled "SDMODELH7V2". + + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/SDMODEL_H7V2.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/SDMODEL_H7V2.jpg new file mode 100644 index 0000000000000..3e0e82a089d9f Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/SDMODEL_H7V2.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/defaults.parm new file mode 100644 index 0000000000000..634b71eec4a77 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/defaults.parm @@ -0,0 +1,6 @@ +# setup for LEDs on chan9 +SERVO9_FUNCTION 120 +SERIAL7_PROTOCOL 16 +# UART1 for DisplayPort Goggles +SERIAL1_PROTOCOL 42 +OSD_TYPE2 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef-bl.dat new file mode 100644 index 0000000000000..3fc10b4278836 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef-bl.dat @@ -0,0 +1,7 @@ +include ../KakuteH7-bdshot/hwdef-bl.dat + +# board ID for firmware load +APJ_BOARD_ID AP_HW_SDMODELH7V2 + +# VTX power switch +PB11 VTX_PWR OUTPUT HIGH PUSHPULL GPIO(81) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef.dat new file mode 100644 index 0000000000000..a59687c3bf6c6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V2/hwdef.dat @@ -0,0 +1,18 @@ +include ../KakuteH7-bdshot/hwdef.dat + +# board ID for firmware load +APJ_BOARD_ID AP_HW_SDMODELH7V2 + +# VTX power switch +PB11 VTX_PWR OUTPUT HIGH PUSHPULL GPIO(81) +define RELAY2_PIN_DEFAULT 81 + +# Camera control +PE9 CAM_C OUTPUT LOW GPIO(84) +define RELAY4_PIN_DEFAULT 84 + +# BetaFlight motor order +define HAL_FRAME_TYPE_DEFAULT 12 + +# builtin compass +COMPASS IST8310 I2C:0:0x0E false ROTATION_PITCH_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef.dat index 1b29f08b0c195..b96f7f01b2d4a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/hwdef.dat @@ -176,3 +176,5 @@ define HAL_OS_FATFS_IO 1 define BOARD_PWM_COUNT_DEFAULT 9 define HAL_STORAGE_SIZE 16384 + +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat index 905b6516156a8..982cef7df8cf6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat @@ -176,7 +176,7 @@ SPIDEV imu3 SPI2 DEVID2 IMU3_CS MODE3 2*MHZ 8*MHZ SPIDEV ramtron SPI4 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ SPIDEV dps310 SPI4 DEVID2 BAROMETER_CS MODE3 5*MHZ 5*MHZ SPIDEV bmp388 SPI4 DEVID3 BAROMETER_CS MODE3 5*MHZ 5*MHZ -SPIDEV rm3100 SPI1 DEVID2 COMPASS_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI1 DEVID2 COMPASS_CS MODE3 1*MHZ 1*MHZ # IMU1 IMU Invensense SPI:imu1 ROTATION_PITCH_180_YAW_90 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat index 36fc767074f6c..4ffdf5d9e3741 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoNexus/hwdef.dat @@ -142,7 +142,7 @@ PC7 SENSORS_SPI4_EN OUTPUT HIGH SPIDEV adis16470 SPI2 DEVID1 CS_ADIS16470 MODE3 1*MHZ 2*MHZ SPIDEV icm40609d SPI3 DEVID2 CS_ICM40609D MODE3 16*MHZ 16*MHZ -SPIDEV rm3100 SPI3 DEVID4 CS_RM3100 MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI3 DEVID4 CS_RM3100 MODE3 1*MHZ 1*MHZ SPIDEV dps310 SPI4 DEVID3 CS_DPS310 MODE3 5*MHZ 5*MHZ SPIDEV ramtron SPI4 DEVID10 CS_FRAM MODE3 8*MHZ 8*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/rFCU/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/rFCU/hwdef.dat index a4282d1b03480..6f49c80ba0b56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/rFCU/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/rFCU/hwdef.dat @@ -234,7 +234,7 @@ PJ4 VDD_5V_PERIPH_nOC INPUT PULLUP # SPI devices SPIDEV adis16470 SPI1 DEVID1 ADIS16470_CS MODE3 1*MHZ 2*MHZ -SPIDEV rm3100 SPI1 DEVID2 RM3100_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI1 DEVID2 RM3100_CS MODE3 1*MHZ 1*MHZ SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat index 514dabe0ebdb7..30c6e5c254a36 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat @@ -78,7 +78,7 @@ PB0 MAG_CS CS PA10 GPS_PPS_IN INPUT # SPI devices -SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE3 2*MHZ 8*MHZ +SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE3 1*MHZ 1*MHZ # compass COMPASS RM3100 SPI:rm3100 false ROTATION_NONE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py index 1e8f9a53f964f..8e183f27bbf36 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py @@ -370,6 +370,8 @@ def convert_file(fname, board_id): for led in sorted(functions["LED"].values()): if (led[3].endswith('_STRIP')): pin = led[1] + if not pin in timers.keys(): + continue timer = timers[pin] nmotors = nmotors+1 f.write("%s %s_%s %s PWM(%s) GPIO(%s) # M%s\n" % (led[1], timer[1], timer[2], timer[1], nmotors, 49+nmotors, nmotors)) @@ -382,7 +384,7 @@ def convert_file(fname, board_id): f.write("define HAL_GPIO_LED_OFF 1\n") # write out devices - if settings['blackbox_device'] == 'SPIFLASH': + if 'blackbox_device' in settings and settings['blackbox_device'] == 'SPIFLASH' or 'USE_FLASH' in defines: write_flash_config(f, settings['flash_spi_bus']) if 'max7456_spi_bus' in settings: diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index bfefb6c253cb7..ea42bc89e6efb 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -343,7 +343,7 @@ void AP_IOMCU::thread_main(void) // update failsafe pwm if (pwm_out.failsafe_pwm_set != pwm_out.failsafe_pwm_sent) { uint8_t set = pwm_out.failsafe_pwm_set; - if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.failsafe_pwm)) { + if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_RC_CHANNELS, pwm_out.failsafe_pwm)) { pwm_out.failsafe_pwm_sent = set; } } @@ -369,7 +369,7 @@ void AP_IOMCU::send_servo_out() if (rate.sbus_rate_hz == 0) { n = MIN(n, 8); } else { - n = MIN(n, IOMCU_MAX_CHANNELS); + n = MIN(n, IOMCU_MAX_RC_CHANNELS); } uint32_t now = AP_HAL::micros(); if (now - last_servo_out_us >= 2000 || AP_BoardConfig::io_dshot()) { @@ -786,7 +786,7 @@ bool AP_IOMCU::modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, void AP_IOMCU::write_channel(uint8_t chan, uint16_t pwm) { - if (chan >= IOMCU_MAX_CHANNELS) { + if (chan >= IOMCU_MAX_RC_CHANNELS) { // could be SBUS out return; } if (chan >= pwm_out.num_channels) { @@ -1107,7 +1107,7 @@ bool AP_IOMCU::check_crc(void) void AP_IOMCU::set_failsafe_pwm(uint16_t chmask, uint16_t period_us) { bool changed = false; - for (uint8_t i=0; i 0)) { + while ((i < IOMCU_MAX_RC_CHANNELS) && (num_values > 0)) { /* XXX range-check value? */ if (rx_io_packet.regs[i] != PWM_IGNORE_THIS_CHANNEL) { reg_direct_pwm.pwm[i] = rx_io_packet.regs[i]; @@ -1216,7 +1216,7 @@ void AP_IOMCU_FW::rcout_config_update(void) */ void AP_IOMCU_FW::fill_failsafe_pwm(void) { - for (uint8_t i=0; i 0 && mixing.rc_channel[i] <= IOMCU_MAX_CHANNELS) { + if (mixing.rc_channel[i] > 0 && mixing.rc_channel[i] <= IOMCU_MAX_RC_CHANNELS) { uint8_t chan = mixing.rc_channel[i]-1; if (i == 2 && !mixing.throttle_is_angle) { rcin[i] = mix_input_range(i, rc_input.pwm[chan]); @@ -141,7 +141,7 @@ void AP_IOMCU_FW::run_mixer(void) } } - for (uint8_t i=0; iset_camera_source(i, (AP_Camera::CameraSource)cmd.content.set_camera_source.primary_source, (AP_Camera::CameraSource)cmd.content.set_camera_source.secondary_source); + } + return ret; + } + return camera->set_camera_source(cmd.content.set_camera_source.instance-1, (AP_Camera::CameraSource)cmd.content.set_camera_source.primary_source, (AP_Camera::CameraSource)cmd.content.set_camera_source.secondary_source); +#endif + case MAV_CMD_IMAGE_START_CAPTURE: // check if this is a single picture request (e.g. total images is 1 or interval and total images are zero) if ((cmd.content.image_start_capture.total_num_images == 1) || diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index b6e7543ec01ce..3bfed9c2924f6 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -249,7 +249,7 @@ void AP_Mount::set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode) backend->set_mode(mode); } -// set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) +// set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle void AP_Mount::set_yaw_lock(uint8_t instance, bool yaw_lock) { @@ -358,6 +358,12 @@ MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_com return MAV_RESULT_ACCEPTED; } + // if neither angles nor rates were provided set the RC_TARGETING yaw lock state + if (isnan(pitch_angle_deg) && isnan(yaw_angle_deg) && isnan(pitch_rate_degs) && isnan(yaw_rate_degs)) { + backend->set_yaw_lock(flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; } @@ -498,6 +504,12 @@ void AP_Mount::handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg) backend->set_rate_target(0, pitch_rate_degs, yaw_rate_degs, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); return; } + + // if neither angles nor rates were provided set the RC_TARGETING yaw lock state + if (isnan(packet.pitch) && isnan(packet.yaw) && isnan(packet.pitch_rate) && isnan(packet.yaw_rate)) { + backend->set_yaw_lock(flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + return; + } } MAV_RESULT AP_Mount::handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet) @@ -833,6 +845,19 @@ bool AP_Mount::set_lens(uint8_t instance, uint8_t lens) return backend->set_lens(lens); } +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t +bool AP_Mount::set_camera_source(uint8_t instance, uint8_t primary_source, uint8_t secondary_source) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->set_camera_source(primary_source, secondary_source); +} +#endif + // send camera information message to GCS void AP_Mount::send_camera_information(uint8_t instance, mavlink_channel_t chan) const { @@ -873,6 +898,16 @@ bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) con return backend->get_rangefinder_distance(distance_m); } +// enable/disable rangefinder. Returns true on success +bool AP_Mount::set_rangefinder_enable(uint8_t instance, bool enable) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->set_rangefinder_enable(enable); +} + AP_Mount_Backend *AP_Mount::get_primary() const { return get_instance(_primary); diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 3763a4f822118..d67526302a643 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -151,7 +151,7 @@ class AP_Mount void set_mode_to_default() { set_mode_to_default(_primary); } void set_mode_to_default(uint8_t instance); - // set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) + // set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle void set_yaw_lock(bool yaw_lock) { set_yaw_lock(_primary, yaw_lock); } void set_yaw_lock(uint8_t instance, bool yaw_lock); @@ -250,6 +250,12 @@ class AP_Mount // set camera lens as a value from 0 to 5 bool set_lens(uint8_t instance, uint8_t lens); +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t + bool set_camera_source(uint8_t instance, uint8_t primary_source, uint8_t secondary_source); +#endif + // send camera information message to GCS void send_camera_information(uint8_t instance, mavlink_channel_t chan) const; @@ -266,6 +272,9 @@ class AP_Mount // get rangefinder distance. Returns true on success bool get_rangefinder_distance(uint8_t instance, float& distance_m) const; + // enable/disable rangefinder. Returns true on success + bool set_rangefinder_enable(uint8_t instance, bool enable); + // parameter var table static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 28536134adaee..a90689802698a 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -91,6 +91,11 @@ void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float y // set the mode to mavlink targeting set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); + + // optionally set RC_TARGETING yaw lock state + if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) { + set_yaw_lock(yaw_is_earth_frame); + } } // sets rate target in deg/s @@ -106,6 +111,11 @@ void AP_Mount_Backend::set_rate_target(float roll_degs, float pitch_degs, float // set the mode to mavlink targeting set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); + + // optionally set RC_TARGETING yaw lock state + if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) { + set_yaw_lock(yaw_is_earth_frame); + } } // set_roi_target - sets target location that mount should attempt to point towards @@ -117,6 +127,11 @@ void AP_Mount_Backend::set_roi_target(const Location &target_loc) // set the mode to GPS tracking mode set_mode(MAV_MOUNT_MODE_GPS_POINT); + + // optionally set RC_TARGETING yaw lock state + if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) { + set_yaw_lock(true); + } } // clear_roi_target - clears target location that mount should attempt to point towards @@ -139,6 +154,11 @@ void AP_Mount_Backend::set_target_sysid(uint8_t sysid) // set the mode to sysid tracking mode set_mode(MAV_MOUNT_MODE_SYSID_TARGET); + + // optionally set RC_TARGETING yaw lock state + if (option_set(Options::RCTARGETING_LOCK_FROM_PREVMODE)) { + set_yaw_lock(true); + } } #if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED @@ -598,6 +618,13 @@ void AP_Mount_Backend::set_rctargeting_on_rcinput_change() const int16_t pitch_in = (pitch_ch == nullptr) ? 0 : pitch_ch->get_radio_in(); const int16_t yaw_in = (yaw_ch == nullptr) ? 0 : yaw_ch->get_radio_in(); + if (!last_rc_input.initialised) { + // The first time through, initial RC inputs should be set, but not used + last_rc_input.initialised = true; + last_rc_input.roll_in = roll_in; + last_rc_input.pitch_in = pitch_in; + last_rc_input.yaw_in = yaw_in; + } // if not in RC_TARGETING or RETRACT modes then check for RC change if (get_mode() != MAV_MOUNT_MODE_RC_TARGETING && get_mode() != MAV_MOUNT_MODE_RETRACT) { // get dead zones @@ -609,11 +636,11 @@ void AP_Mount_Backend::set_rctargeting_on_rcinput_change() if ((abs(last_rc_input.roll_in - roll_in) > roll_dz) || (abs(last_rc_input.pitch_in - pitch_in) > pitch_dz) || (abs(last_rc_input.yaw_in - yaw_in) > yaw_dz)) { - set_mode(MAV_MOUNT_MODE_RC_TARGETING); + set_mode(MAV_MOUNT_MODE_RC_TARGETING); } } - // if in RC_TARGETING or RETRACT mode then store last RC input + // if NOW in RC_TARGETING or RETRACT mode then store last RC input (mode might have changed) if (get_mode() == MAV_MOUNT_MODE_RC_TARGETING || get_mode() == MAV_MOUNT_MODE_RETRACT) { last_rc_input.roll_in = roll_in; last_rc_input.pitch_in = pitch_in; @@ -797,10 +824,45 @@ void AP_Mount_Backend::update_angle_target_from_rate(const MountTarget& rate_rad // helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message uint16_t AP_Mount_Backend::get_gimbal_device_flags() const { + // get yaw lock state by mode + bool yaw_lock_state = false; + switch (_mode) { + case MAV_MOUNT_MODE_RETRACT: + case MAV_MOUNT_MODE_NEUTRAL: + // these modes always use body-frame yaw (aka follow) + yaw_lock_state = false; + break; + case MAV_MOUNT_MODE_MAVLINK_TARGETING: + switch (mnt_target.target_type) { + case MountTargetType::RATE: + yaw_lock_state = mnt_target.rate_rads.yaw_is_ef; + break; + case MountTargetType::ANGLE: + yaw_lock_state = mnt_target.angle_rad.yaw_is_ef; + break; + } + break; + case MAV_MOUNT_MODE_RC_TARGETING: + yaw_lock_state = _yaw_lock; + break; + case MAV_MOUNT_MODE_GPS_POINT: + case MAV_MOUNT_MODE_SYSID_TARGET: + case MAV_MOUNT_MODE_HOME_LOCATION: + // these modes always use earth-frame yaw (aka lock) + yaw_lock_state = true; + break; + case MAV_MOUNT_MODE_ENUM_END: + // unsupported + yaw_lock_state = false; + break; + } + const uint16_t flags = (get_mode() == MAV_MOUNT_MODE_RETRACT ? GIMBAL_DEVICE_FLAGS_RETRACT : 0) | (get_mode() == MAV_MOUNT_MODE_NEUTRAL ? GIMBAL_DEVICE_FLAGS_NEUTRAL : 0) | GIMBAL_DEVICE_FLAGS_ROLL_LOCK | // roll angle is always earth-frame - GIMBAL_DEVICE_FLAGS_PITCH_LOCK; // pitch angle is always earth-frame, yaw_angle is always body-frame + GIMBAL_DEVICE_FLAGS_PITCH_LOCK| // pitch angle is always earth-frame, yaw_angle is always body-frame + GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME | // yaw angle is always in vehicle-frame + (yaw_lock_state ? GIMBAL_DEVICE_FLAGS_YAW_LOCK : 0); return flags; } diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index f75ea29da5289..56706d7463c98 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -79,7 +79,7 @@ class AP_Mount_Backend // set mount's mode bool set_mode(enum MAV_MOUNT_MODE mode); - // set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) + // set yaw_lock used in RC_TARGETING mode. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle void set_yaw_lock(bool yaw_lock) { _yaw_lock = yaw_lock; } @@ -182,6 +182,12 @@ class AP_Mount_Backend // set camera lens as a value from 0 to 5 virtual bool set_lens(uint8_t lens) { return false; } +#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t + virtual bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) { return false; } +#endif + // send camera information message to GCS virtual void send_camera_information(mavlink_channel_t chan) const {} @@ -203,6 +209,9 @@ class AP_Mount_Backend // get rangefinder distance. Returns true on success virtual bool get_rangefinder_distance(float& distance_m) const { return false; } + // enable/disable rangefinder. Returns true on success + virtual bool set_rangefinder_enable(bool enable) { return false; } + protected: enum class MountTargetType { @@ -228,6 +237,12 @@ class AP_Mount_Backend void set(const Vector3f& rpy, bool yaw_is_ef_in); }; + // options parameter bitmask handling + enum class Options : uint8_t { + RCTARGETING_LOCK_FROM_PREVMODE = (1U << 0), // RC_TARGETING mode's lock/follow state maintained from previous mode + }; + bool option_set(Options opt) const { return (_params.options.get() & (uint8_t)opt) != 0; } + // returns true if user has configured a valid yaw angle range // allows user to disable yaw even on 3-axis gimbal bool yaw_range_valid() const { return (_params.yaw_angle_min < _params.yaw_angle_max); } @@ -283,7 +298,7 @@ class AP_Mount_Backend uint8_t _instance; // this instance's number MAV_MOUNT_MODE _mode; // current mode (see MAV_MOUNT_MODE enum) - bool _yaw_lock; // True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame + bool _yaw_lock; // yaw_lock used in RC_TARGETING mode. True if the gimbal's yaw target is maintained in earth-frame, if false (aka "follow") it is maintained in body-frame // structure for MAVLink Targeting angle and rate targets struct { @@ -314,6 +329,7 @@ class AP_Mount_Backend // structure holding the last RC inputs struct { + bool initialised; int16_t roll_in; int16_t pitch_in; int16_t yaw_in; diff --git a/libraries/AP_Mount/AP_Mount_Params.cpp b/libraries/AP_Mount/AP_Mount_Params.cpp index c811afde8418d..57257eb5e4e2b 100644 --- a/libraries/AP_Mount/AP_Mount_Params.cpp +++ b/libraries/AP_Mount/AP_Mount_Params.cpp @@ -165,6 +165,13 @@ const AP_Param::GroupInfo AP_Mount_Params::var_info[] = { // @User: Advanced AP_GROUPINFO_FLAGS("_DEVID", 15, AP_Mount_Params, dev_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY), + // @Param: _OPTIONS + // @DisplayName: Mount options + // @Description: Mount options bitmask + // @Bitmask: 0:RC lock state from previous mode + // @User: Standard + AP_GROUPINFO("_OPTIONS", 16, AP_Mount_Params, options, 0), + AP_GROUPEND }; diff --git a/libraries/AP_Mount/AP_Mount_Params.h b/libraries/AP_Mount/AP_Mount_Params.h index a3d7e12b01b6e..ccf42c1fe050c 100644 --- a/libraries/AP_Mount/AP_Mount_Params.h +++ b/libraries/AP_Mount/AP_Mount_Params.h @@ -31,4 +31,5 @@ class AP_Mount_Params { AP_Float pitch_stb_lead; // pitch lead control gain (only used by servo backend) AP_Int8 sysid_default; // target sysid for mount to follow AP_Int32 dev_id; // Device id taking into account bus + AP_Int8 options; // mount options bitmask }; diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index c33fb3ec94a52..c8e2ae78d2f20 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -962,6 +962,64 @@ bool AP_Mount_Siyi::set_lens(uint8_t lens) return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type); } +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t +bool AP_Mount_Siyi::set_camera_source(uint8_t primary_source, uint8_t secondary_source) +{ + // only supported on ZT30. sanity check lens values + if (_hardware_model != HardwareModel::ZT30) { + return false; + } + + // maps primary and secondary source to siyi camera image type + CameraImageType cam_image_type; + switch (primary_source) { + case 0: // Default (RGB) + FALLTHROUGH; + case 1: // RGB + switch (secondary_source) { + case 0: // RGB + Default (None) + cam_image_type = CameraImageType::MAIN_ZOOM_SUB_THERMAL; // 3 + break; + case 2: // PIP RGB+IR + cam_image_type = CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE; // 0 + break; + case 4: // PIP RGB+RGB_WIDEANGLE + cam_image_type = CameraImageType::MAIN_PIP_ZOOM_WIDEANGLE_SUB_THERMAL; // 2 + break; + default: + return false; + } + break; + case 2: // IR + switch (secondary_source) { + case 0: // IR + Default (None) + cam_image_type = CameraImageType::MAIN_THERMAL_SUB_ZOOM; // 7 + break; + default: + return false; + } + break; + case 4: // RGB_WIDEANGLE + switch (secondary_source) { + case 0: // RGB_WIDEANGLE + Default (None) + cam_image_type = CameraImageType::MAIN_WIDEANGLE_SUB_THERMAL; // 5 + break; + case 2: // PIP RGB_WIDEANGLE+IR + cam_image_type = CameraImageType::MAIN_PIP_WIDEANGLE_THERMAL_SUB_ZOOM; // 1 + break; + default: + return false; + } + break; + default: + return false; + } + + // send desired image type to camera + return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type); +} + // send camera information message to GCS void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const { diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 2245e4ca0dd34..6036a8b635b5b 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -75,6 +75,10 @@ class AP_Mount_Siyi : public AP_Mount_Backend // set camera lens as a value from 0 to 8. ZT30 only bool set_lens(uint8_t lens) override; + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t + bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override; + // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override; diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 5e08762348071..4dd78a82c51c9 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -573,22 +573,23 @@ bool AP_Mount_Viewpro::send_target_angles(float pitch_rad, float yaw_rad, bool y } // send camera command, affected image sensor and value (e.g. zoom speed) -bool AP_Mount_Viewpro::send_camera_command(ImageSensor img_sensor, CameraCommand cmd, uint8_t value) +bool AP_Mount_Viewpro::send_camera_command(ImageSensor img_sensor, CameraCommand cmd, uint8_t value, LRFCommand lrf_cmd) { // fill in 2 bytes containing sensor, zoom speed, operation command and LRF // bit0~2: sensor // bit3~5: zoom speed // bit6~12: operation command no - // bit13~15: LRF command (unused) + // bit13~15: LRF command const uint16_t sensor_id = (uint16_t)img_sensor; const uint16_t zoom_speed = ((uint16_t)value & 0x07) << 3; const uint16_t operation_cmd = ((uint16_t)cmd & 0x7F) << 6; + const uint16_t rangefinder_cmd = ((uint16_t)lrf_cmd & 0x07) << 13; // fill in packet const C1Packet c1_packet { .content = { frame_id: FrameId::C1, - sensor_zoom_cmd_be: htobe16(sensor_id | zoom_speed | operation_cmd) + sensor_zoom_cmd_be: htobe16(sensor_id | zoom_speed | operation_cmd | rangefinder_cmd) } }; @@ -862,6 +863,47 @@ bool AP_Mount_Viewpro::set_lens(uint8_t lens) return send_camera_command(new_image_sensor, CameraCommand::NO_ACTION, 0); } +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t +bool AP_Mount_Viewpro::set_camera_source(uint8_t primary_source, uint8_t secondary_source) +{ + // maps primary and secondary source to viewpro image sensor + ImageSensor new_image_sensor; + switch (primary_source) { + case 0: // Default (RGB) + FALLTHROUGH; + case 1: // RGB + switch (secondary_source) { + case 0: // RGB + Default (None) + new_image_sensor = ImageSensor::EO1; + break; + case 2: // PIP RGB+IR + new_image_sensor = ImageSensor::EO1_IR_PIP; + break; + default: + return false; + } + break; + case 2: // IR + switch (secondary_source) { + case 0: // IR + Default (None) + new_image_sensor = ImageSensor::IR; + break; + case 1: // PIP IR+RGB + new_image_sensor = ImageSensor::IR_EO1_PIP; + break; + default: + return false; + } + break; + default: + return false; + } + + // send desired image type to camera + return send_camera_command(new_image_sensor, CameraCommand::NO_ACTION, 0); +} + // send camera information message to GCS void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const { @@ -939,4 +981,10 @@ bool AP_Mount_Viewpro::get_rangefinder_distance(float& distance_m) const return true; } +// enable/disable rangefinder. Returns true on success +bool AP_Mount_Viewpro::set_rangefinder_enable(bool enable) +{ + return send_camera_command(ImageSensor::NO_ACTION, CameraCommand::NO_ACTION, 0, enable ? LRFCommand::CONTINUOUS_RANGING_START : LRFCommand::STOP_RANGING); +} + #endif // HAL_MOUNT_VIEWPRO_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.h b/libraries/AP_Mount/AP_Mount_Viewpro.h index ed312a2035946..1ddaa283212be 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.h +++ b/libraries/AP_Mount/AP_Mount_Viewpro.h @@ -78,6 +78,10 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // set camera lens as a value from 0 to 5 bool set_lens(uint8_t lens) override; + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t + bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override; + // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override; @@ -91,6 +95,9 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // get rangefinder distance. Returns true on success bool get_rangefinder_distance(float& distance_m) const override; + // enable/disable rangefinder. Returns true on success + bool set_rangefinder_enable(bool enable) override; + protected: // get attitude as a quaternion. returns true on success @@ -157,6 +164,15 @@ class AP_Mount_Viewpro : public AP_Mount_Backend MANUAL_FOCUS = 0x1A }; + // C1 rangefinder commands + enum class LRFCommand : uint8_t { + NO_ACTION = 0x00, + SINGLE_RANGING = 0x01, + CONTINUOUS_RANGING_START = 0x02, + LPCL_CONTINUOUS_RANGING_START = 0x03, + STOP_RANGING = 0x05 + }; + // C2 camera commands enum class CameraCommand2 : uint8_t { SET_EO_ZOOM = 0x53 @@ -347,7 +363,7 @@ class AP_Mount_Viewpro : public AP_Mount_Backend bool send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef); // send camera command, affected image sensor and value (e.g. zoom speed) - bool send_camera_command(ImageSensor img_sensor, CameraCommand cmd, uint8_t value); + bool send_camera_command(ImageSensor img_sensor, CameraCommand cmd, uint8_t value, LRFCommand lrf_cmd = LRFCommand::NO_ACTION); // send camera command2 and corresponding value (e.g. zoom as absolute value) bool send_camera_command2(CameraCommand2 cmd, uint16_t value); diff --git a/libraries/AP_Mount/AP_Mount_Xacti.cpp b/libraries/AP_Mount/AP_Mount_Xacti.cpp index 239d416455abc..3d551885ce35d 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.cpp +++ b/libraries/AP_Mount/AP_Mount_Xacti.cpp @@ -308,6 +308,48 @@ bool AP_Mount_Xacti::set_lens(uint8_t lens) return set_param_int32(Param::SensorMode, lens); } +// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type +// primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t +bool AP_Mount_Xacti::set_camera_source(uint8_t primary_source, uint8_t secondary_source) +{ + // maps primary and secondary source to xacti SensorsMode + SensorsMode new_sensor_mode; + switch (primary_source) { + case 0: // Default (RGB) + FALLTHROUGH; + case 1: // RGB + switch (secondary_source) { + case 0: // RGB + Default (None) + new_sensor_mode = SensorsMode::RGB; + break; + case 2: // PIP RGB+IR + new_sensor_mode = SensorsMode::PIP; + break; + default: + return false; + } + break; + case 2: // IR + if (secondary_source != 0) { + return false; + } + new_sensor_mode = SensorsMode::IR; + break; + case 3: // NDVI + if (secondary_source != 0) { + return false; + } + // NDVI + Default (None) + new_sensor_mode = SensorsMode::NDVI; + break; + default: + return false; + } + + // send desired sensor mode to camera + return set_param_int32(Param::SensorMode, (uint8_t)new_sensor_mode); +} + // send camera information message to GCS void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const { diff --git a/libraries/AP_Mount/AP_Mount_Xacti.h b/libraries/AP_Mount/AP_Mount_Xacti.h index 247a66bac1cbb..fc4b20db03bb7 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.h +++ b/libraries/AP_Mount/AP_Mount_Xacti.h @@ -62,6 +62,10 @@ class AP_Mount_Xacti : public AP_Mount_Backend // set camera lens as a value from 0 to 5 bool set_lens(uint8_t lens) override; + // set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type + // primary and secondary sources use the AP_Camera::CameraSource enum cast to uint8_t + bool set_camera_source(uint8_t primary_source, uint8_t secondary_source) override; + // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override; diff --git a/libraries/AP_Mount/AP_Mount_config.h b/libraries/AP_Mount/AP_Mount_config.h index 9159653dcc79e..6b14bcb4807ee 100644 --- a/libraries/AP_Mount/AP_Mount_config.h +++ b/libraries/AP_Mount/AP_Mount_config.h @@ -53,3 +53,8 @@ #ifndef AP_MOUNT_POI_TO_LATLONALT_ENABLED #define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && BOARD_FLASH_SIZE > 1024 #endif + +// set camera source is supported on gimbals that may have more than one lens +#ifndef HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED +#define HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED HAL_MOUNT_SIYI_ENABLED || HAL_MOUNT_XACTI_ENABLED || HAL_MOUNT_VIEWPRO_ENABLED +#endif diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp index d2179f348cbed..33a796b2ba6c7 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp @@ -209,6 +209,24 @@ void NavEKF3_core::updateStateIndexLim() } } +// set the default yaw source +void NavEKF3_core::setYawSource() +{ + AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); + if (wasLearningCompass_ms > 0) { + // can't use compass while it is being calibrated + if (yaw_source == AP_NavEKF_Source::SourceYaw::COMPASS) { + yaw_source = AP_NavEKF_Source::SourceYaw::NONE; + } else if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { + yaw_source = AP_NavEKF_Source::SourceYaw::GPS; + } + } + if (yaw_source != yaw_source_last) { + yaw_source_last = yaw_source; + yaw_source_reset = true; + } +} + // Set inertial navigation aiding mode void NavEKF3_core::setAidingMode() { @@ -218,6 +236,8 @@ void NavEKF3_core::setAidingMode() // Save the previous status so we can detect when it has changed PV_AidingModePrev = PV_AidingMode; + setYawSource(); + // Check that the gyro bias variance has converged checkGyroCalStatus(); @@ -583,9 +603,8 @@ bool NavEKF3_core::readyToUseExtNav(void) const // return true if we should use the compass bool NavEKF3_core::use_compass(void) const { - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - if ((yaw_source != AP_NavEKF_Source::SourceYaw::COMPASS) && - (yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { + if ((yaw_source_last != AP_NavEKF_Source::SourceYaw::COMPASS) && + (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { // not using compass as a yaw source return false; } @@ -598,14 +617,13 @@ bool NavEKF3_core::use_compass(void) const // are we using (aka fusing) a non-compass yaw? bool NavEKF3_core::using_noncompass_for_yaw(void) const { - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); #if EK3_FEATURE_EXTERNAL_NAV - if (yaw_source == AP_NavEKF_Source::SourceYaw::EXTNAV) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV) { return ((imuSampleTime_ms - last_extnav_yaw_fusion_ms < 5000) || (imuSampleTime_ms - lastSynthYawTime_ms < 5000)); } #endif - if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS || yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || - yaw_source == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS || yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || + yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()) { return imuSampleTime_ms - last_gps_yaw_ms < 5000 || imuSampleTime_ms - lastSynthYawTime_ms < 5000; } return false; @@ -615,7 +633,7 @@ bool NavEKF3_core::using_noncompass_for_yaw(void) const bool NavEKF3_core::using_extnav_for_yaw() const { #if EK3_FEATURE_EXTERNAL_NAV - if (frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::EXTNAV) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV) { return ((imuSampleTime_ms - last_extnav_yaw_fusion_ms < 5000) || (imuSampleTime_ms - lastSynthYawTime_ms < 5000)); } #endif @@ -685,9 +703,8 @@ void NavEKF3_core::checkGyroCalStatus(void) { // check delta angle bias variances const ftype delAngBiasVarMax = sq(radians(0.15 * dtEkfAvg)); - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - if (!use_compass() && (yaw_source != AP_NavEKF_Source::SourceYaw::GPS) && (yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) && - (yaw_source != AP_NavEKF_Source::SourceYaw::EXTNAV)) { + if (!use_compass() && (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS) && (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) && + (yaw_source_last != AP_NavEKF_Source::SourceYaw::EXTNAV)) { // rotate the variances into earth frame and evaluate horizontal terms only as yaw component is poorly observable without a yaw reference // which can make this check fail const Vector3F delAngBiasVarVec { P[10][10], P[11][11], P[12][12] }; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp index 330befc9d1d2b..e8b635e560fed 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp @@ -6,6 +6,13 @@ #include #include +// minimum GPS horizontal speed required to use GPS ground course for yaw alignment (m/s) +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + #define GPS_VEL_YAW_ALIGN_MIN_SPD 5.0F +#else + #define GPS_VEL_YAW_ALIGN_MIN_SPD 1.0F +#endif + /******************************************************** * RESET FUNCTIONS * ********************************************************/ @@ -151,7 +158,7 @@ void NavEKF3_core::realignYawGPS(bool emergency_reset) if (badMagYaw) { // attempt to use EKF-GSF estimate if available as it is more robust to GPS glitches // by default fly forward vehicles use ground course for initial yaw unless the GSF is explicitly selected as the yaw source - const bool useGSF = !assume_zero_sideslip() || (frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::GSF); + const bool useGSF = !assume_zero_sideslip() || (yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF); if (useGSF && EKFGSF_resetMainFilterYaw(emergency_reset)) { return; } @@ -214,13 +221,6 @@ void NavEKF3_core::SelectMagFusion() // used for load levelling magFusePerformed = false; - // get default yaw source - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - if (yaw_source != yaw_source_last) { - yaw_source_last = yaw_source; - yaw_source_reset = true; - } - // Store yaw angle when moving for use as a static reference when not moving if (!onGroundNotMoving) { if (fabsF(prevTnb[0][2]) < fabsF(prevTnb[1][2])) { @@ -238,13 +238,13 @@ void NavEKF3_core::SelectMagFusion() // Handle case where we are not using a yaw sensor of any type and attempt to reset the yaw in // flight using the output from the GSF yaw estimator or GPS ground course. - if ((yaw_source == AP_NavEKF_Source::SourceYaw::GSF) || + if ((yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF) || (!use_compass() && - yaw_source != AP_NavEKF_Source::SourceYaw::GPS && - yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK && - yaw_source != AP_NavEKF_Source::SourceYaw::EXTNAV)) { + yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS && + yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK && + yaw_source_last != AP_NavEKF_Source::SourceYaw::EXTNAV)) { - if ((!yawAlignComplete || yaw_source_reset) && ((yaw_source != AP_NavEKF_Source::SourceYaw::GSF) || (EKFGSF_yaw_valid_count >= GSF_YAW_VALID_HISTORY_THRESHOLD))) { + if ((!yawAlignComplete || yaw_source_reset) && ((yaw_source_last != AP_NavEKF_Source::SourceYaw::GSF) || (EKFGSF_yaw_valid_count >= GSF_YAW_VALID_HISTORY_THRESHOLD))) { realignYawGPS(false); yaw_source_reset = false; } else { @@ -255,7 +255,7 @@ void NavEKF3_core::SelectMagFusion() // use the EKF-GSF yaw estimator output as this is more robust than the EKF can achieve without a yaw measurement // for non fixed wing platform types ftype gsfYaw, gsfYawVariance; - const bool didUseEKFGSF = yawAlignComplete && (yaw_source == AP_NavEKF_Source::SourceYaw::GSF) && EKFGSF_getYaw(gsfYaw, gsfYawVariance) && !assume_zero_sideslip() && fuseEulerYaw(yawFusionMethod::GSF); + const bool didUseEKFGSF = yawAlignComplete && (yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF) && EKFGSF_getYaw(gsfYaw, gsfYawVariance) && !assume_zero_sideslip() && fuseEulerYaw(yawFusionMethod::GSF); // fallback methods if (!didUseEKFGSF) { @@ -276,7 +276,7 @@ void NavEKF3_core::SelectMagFusion() } // Handle case where we are using GPS yaw sensor instead of a magnetomer - if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS || yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS || yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { bool have_fused_gps_yaw = false; if (storedYawAng.recall(yawAngDataDelayed,imuDataDelayed.time_ms)) { if (tiltAlignComplete && (!yawAlignComplete || yaw_source_reset)) { @@ -312,7 +312,7 @@ void NavEKF3_core::SelectMagFusion() yaw_source_reset = true; } - if (yaw_source == AP_NavEKF_Source::SourceYaw::GPS) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS) { // no fallback return; } @@ -355,7 +355,7 @@ void NavEKF3_core::SelectMagFusion() #if EK3_FEATURE_EXTERNAL_NAV // Handle case where we are using an external nav for yaw const bool extNavYawDataToFuse = storedExtNavYawAng.recall(extNavYawAngDataDelayed, imuDataDelayed.time_ms); - if (yaw_source == AP_NavEKF_Source::SourceYaw::EXTNAV) { + if (yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV) { if (extNavYawDataToFuse) { if (tiltAlignComplete && (!yawAlignComplete || yaw_source_reset)) { alignYawAngle(extNavYawAngDataDelayed); @@ -390,7 +390,7 @@ void NavEKF3_core::SelectMagFusion() magTimeout = true; } - if (yaw_source != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { + if (yaw_source_last != AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK) { // check for and read new magnetometer measurements. We don't // read for GPS_COMPASS_FALLBACK as it has already been read // above @@ -402,8 +402,8 @@ void NavEKF3_core::SelectMagFusion() // Control reset of yaw and magnetic field states if we are using compass data if (magDataToFuse) { - if (yaw_source_reset && (yaw_source == AP_NavEKF_Source::SourceYaw::COMPASS || - yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { + if (yaw_source_reset && (yaw_source_last == AP_NavEKF_Source::SourceYaw::COMPASS || + yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK)) { magYawResetRequest = true; yaw_source_reset = false; } @@ -1566,7 +1566,7 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw(bool emergency_reset) EKFGSF_yaw_reset_ms = imuSampleTime_ms; EKFGSF_yaw_reset_count++; - if ((frontend->sources.getYawSource() == AP_NavEKF_Source::SourceYaw::GSF) || + if ((yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF) || !use_compass() || (dal.compass().get_num_enabled() == 0)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u yaw aligned using GPS",(unsigned)imu_index); } else { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index 9ebe777515a84..258bd6bcf588e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -295,16 +295,10 @@ void NavEKF3_core::readMagData() } if (compass.learn_offsets_enabled()) { - // while learning offsets keep all mag states reset - InitialiseVariablesMag(); wasLearningCompass_ms = imuSampleTime_ms; } else if (wasLearningCompass_ms != 0 && imuSampleTime_ms - wasLearningCompass_ms > 1000) { + // allow time for old data to clear the buffer before signalling other code that compass data can be used wasLearningCompass_ms = 0; - // force a new yaw alignment 1s after learning completes. The - // delay is to ensure any buffered mag samples are discarded - yawAlignComplete = false; - yawAlignGpsValidCount = 0; - InitialiseVariablesMag(); } // If the magnetometer has timed out (been rejected for too long), we find another magnetometer to use if available @@ -1329,9 +1323,8 @@ ftype NavEKF3_core::MagDeclination(void) const */ void NavEKF3_core::updateMovementCheck(void) { - const AP_NavEKF_Source::SourceYaw yaw_source = frontend->sources.getYawSource(); - const bool runCheck = onGround && (yaw_source == AP_NavEKF_Source::SourceYaw::GPS || yaw_source == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || - yaw_source == AP_NavEKF_Source::SourceYaw::EXTNAV || yaw_source == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()); + const bool runCheck = onGround && (yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS || yaw_source_last == AP_NavEKF_Source::SourceYaw::GPS_COMPASS_FALLBACK || + yaw_source_last == AP_NavEKF_Source::SourceYaw::EXTNAV || yaw_source_last == AP_NavEKF_Source::SourceYaw::GSF || !use_compass()); if (!runCheck) { onGroundNotMoving = false; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index 8ba964b7e88fd..8f7b799cb5f82 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -118,9 +118,6 @@ // number of continuous valid GPS velocity samples required to reset yaw #define GPS_VEL_YAW_ALIGN_COUNT_THRESHOLD 5 -// minimum GPS horizontal speed required to use GPS ground course for yaw alignment (m/s) -#define GPS_VEL_YAW_ALIGN_MIN_SPD 5.0F - // maximum GPs ground course uncertainty allowed for yaw alignment (deg) #define GPS_VEL_YAW_ALIGN_MAX_ANG_ERR 15.0F @@ -889,6 +886,9 @@ class NavEKF3_core : public NavEKF_core_common // Determine if we are flying or on the ground void detectFlight(); + // set the default yaw source + void setYawSource(); + // Set inertial navigation aiding mode void setAidingMode(); diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 996960a0b5819..95814d5672d3c 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2078,7 +2078,7 @@ void AP_Param::convert_class(uint16_t param_key, void *object_pointer, convert width of a parameter, allowing update to wider scalar values without changing the parameter indexes */ -bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor) +bool AP_Param::_convert_parameter_width(ap_var_type old_ptype, float scale_factor, bool bitmask) { if (configured_in_storage()) { // already converted or set by the user @@ -2122,10 +2122,46 @@ bool AP_Param::convert_parameter_width(ap_var_type old_ptype, float scale_factor AP_Param *old_ap = (AP_Param *)&old_value[0]; - // going via float is safe as the only time we would be converting - // from AP_Int32 is when converting to float - float old_float_value = old_ap->cast_to_float(old_ptype); - set_value(new_ptype, this, old_float_value*scale_factor); + if (!bitmask) { + // Numeric conversion + // going via float is safe as the only time we would be converting + // from AP_Int32 is when converting to float + float old_float_value = old_ap->cast_to_float(old_ptype); + set_value(new_ptype, this, old_float_value*scale_factor); + + } else { + // Bitmask conversion, go via uint32 + // int8 -1 should convert to int16 255 + uint32_t mask; + switch (old_ptype) { + case AP_PARAM_INT8: + mask = (uint8_t)(*(AP_Int8*)old_ap); + break; + case AP_PARAM_INT16: + mask = (uint16_t)(*(AP_Int16*)old_ap); + break; + case AP_PARAM_INT32: + mask = (uint32_t)(*(AP_Int32*)old_ap); + break; + default: + return false; + } + + switch (new_ptype) { + case AP_PARAM_INT8: + ((AP_Int8 *)this)->set(mask); + break; + case AP_PARAM_INT16: + ((AP_Int16 *)this)->set(mask); + break; + case AP_PARAM_INT32: + ((AP_Int32 *)this)->set(mask); + break; + default: + return false; + } + } + // force save as the new type save(true); diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 85d533c1fd148..fe85e4175ff0f 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -475,11 +475,17 @@ class AP_Param values without changing the parameter indexes. This will return true if the parameter was converted from an old parameter value */ - bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0); + bool convert_parameter_width(ap_var_type old_ptype, float scale_factor=1.0) { + return _convert_parameter_width(old_ptype, scale_factor, false); + } bool convert_centi_parameter(ap_var_type old_ptype) { return convert_parameter_width(old_ptype, 0.01f); } - + // Converting bitmasks should be done bitwise rather than numerically + bool convert_bitmask_parameter_width(ap_var_type old_ptype) { + return _convert_parameter_width(old_ptype, 1.0, true); + } + // convert a single parameter with scaling enum { CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion @@ -765,6 +771,13 @@ class AP_Param // return true if the parameter is configured in EEPROM/FRAM bool configured_in_storage(void) const; + /* + convert width of a parameter, allowing update to wider scalar + values without changing the parameter indexes. This will return + true if the parameter was converted from an old parameter value + */ + bool _convert_parameter_width(ap_var_type old_ptype, float scale_factor, bool bitmask); + // send a parameter to all GCS instances void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp index 75e22b2aaba5f..9d5facdb5af91 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp @@ -48,16 +48,11 @@ bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) { WITH_SEMAPHORE(_sem); - // Time out on incoming data; if we don't get new data in 500ms, dump it - if (now - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { - set_status(_state_pending, RangeFinder::Status::NoData); - } else { - _state_pending.last_reading_ms = now; - _state_pending.distance_m = dist_m; - _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; - _state_pending.voltage_mv = 0; - update_status(_state_pending); - } + _state_pending.last_reading_ms = now; + _state_pending.distance_m = dist_m; + _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; + _state_pending.voltage_mv = 0; + update_status(_state_pending); return true; } @@ -66,6 +61,12 @@ bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) { void AP_RangeFinder_Lua::update(void) { WITH_SEMAPHORE(_sem); + + // Time out on incoming data + if (_state_pending.status != RangeFinder::Status::NotConnected && + AP_HAL::millis() - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { + set_status(_state_pending, RangeFinder::Status::NoData); + } state = _state_pending; } diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index 88b9d921ddc27..2216cc5a33687 100644 --- a/libraries/AP_Scripting/lua/src/ldo.c +++ b/libraries/AP_Scripting/lua/src/ldo.c @@ -142,10 +142,10 @@ int luaD_rawrunprotected (lua_State *L, Pfunc f, void *ud) { lj.status = LUA_OK; lj.previous = L->errorJmp; /* chain new error handler */ L->errorJmp = &lj; - LUAI_TRY(L, &lj, #ifdef ARM_MATH_CM7 __asm__("vpush {s16-s31}"); #endif + LUAI_TRY(L, &lj, (*f)(L, ud); ); #ifdef ARM_MATH_CM7 diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index 5a35ea5b7416d..4a6520914ef5e 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -370,7 +370,7 @@ HarmonicNotchFilterParams::HarmonicNotchFilterParams(void) void HarmonicNotchFilterParams::init() { - _harmonics.convert_parameter_width(AP_PARAM_INT8); + _harmonics.convert_bitmask_parameter_width(AP_PARAM_INT8); } /* diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b1b2ca239929f..cf5680ae01b60 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5180,6 +5180,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_DO_SET_CAM_TRIGG_DIST: case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_SET_CAMERA_FOCUS: + case MAV_CMD_SET_CAMERA_SOURCE: case MAV_CMD_IMAGE_START_CAPTURE: case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_CAMERA_TRACK_POINT: @@ -6635,14 +6636,14 @@ void GCS::passthru_timer(void) uint8_t buf[64]; // read from port1, and write to port2 - int16_t nbytes = _passthru.port1->read_locked(buf, sizeof(buf), lock_key); + int16_t nbytes = _passthru.port1->read_locked(buf, MIN(sizeof(buf),_passthru.port2->txspace()), lock_key); if (nbytes > 0) { _passthru.last_port1_data_ms = AP_HAL::millis(); _passthru.port2->write_locked(buf, nbytes, lock_key); } // read from port2, and write to port1 - nbytes = _passthru.port2->read_locked(buf, sizeof(buf), lock_key); + nbytes = _passthru.port2->read_locked(buf, MIN(sizeof(buf),_passthru.port1->txspace()), lock_key); if (nbytes > 0) { _passthru.port1->write_locked(buf, nbytes, lock_key); } diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index b868d8bb63bbb..95a818a6142bf 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -236,6 +236,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter, Rover, Plane, Blimp}: 174:Camera Image Tracking // @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable + // @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable // @Values{Rover}: 201:Roll // @Values{Rover}: 202:Pitch // @Values{Rover}: 207:MainSail @@ -665,6 +666,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo case AUX_FUNC::LOWEHEISER_STARTER: case AUX_FUNC::MAG_CAL: case AUX_FUNC::CAMERA_IMAGE_TRACKING: + case AUX_FUNC::MOUNT_LRF_ENABLE: break; // not really aux functions: @@ -771,6 +773,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = { { AUX_FUNC::CAMERA_AUTO_FOCUS, "Camera Auto Focus"}, { AUX_FUNC::CAMERA_IMAGE_TRACKING, "Camera Image Tracking"}, { AUX_FUNC::CAMERA_LENS, "Camera Lens"}, + { AUX_FUNC::MOUNT_LRF_ENABLE, "Mount LRF Enable"}, }; /* lookup the announcement for switch change */ @@ -1002,14 +1005,18 @@ bool RC_Channel::do_aux_function_camera_image_tracking(const AuxSwitchPos ch_fla bool RC_Channel::do_aux_function_camera_lens(const AuxSwitchPos ch_flag) { +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED AP_Camera *camera = AP::camera(); if (camera == nullptr) { return false; } // Low selects lens 0 (default), Mediums selects lens1, High selects lens2 return camera->set_lens((uint8_t)ch_flag); +#else + return false; +#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED } -#endif +#endif // AP_CAMERA_ENABLED void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) { @@ -1517,9 +1524,11 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos case AUX_FUNC::CAMERA_IMAGE_TRACKING: return do_aux_function_camera_image_tracking(ch_flag); +#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED case AUX_FUNC::CAMERA_LENS: return do_aux_function_camera_lens(ch_flag); -#endif +#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED +#endif // AP_CAMERA_ENABLED #if HAL_MOUNT_ENABLED case AUX_FUNC::RETRACT_MOUNT1: { @@ -1549,6 +1558,15 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos mount->set_yaw_lock(ch_flag == AuxSwitchPos::HIGH); break; } + + case AUX_FUNC::MOUNT_LRF_ENABLE: { + AP_Mount *mount = AP::mount(); + if (mount == nullptr) { + break; + } + mount->set_rangefinder_enable(0, ch_flag == AuxSwitchPos::HIGH); + break; + } #endif #if HAL_LOGGING_ENABLED diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 5216f2a4ac7ab..2fb05537049b0 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -249,6 +249,7 @@ class RC_Channel { CAMERA_IMAGE_TRACKING = 174, // camera image tracking CAMERA_LENS = 175, // camera lens selection VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method + MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable // inputs from 200 will eventually used to replace RCMAP diff --git a/modules/mavlink b/modules/mavlink index 130a836efbfef..1e04d8b8634da 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 130a836efbfef0eb3287a92cd5e187de7facdce2 +Subproject commit 1e04d8b8634dafc8c9a2496c6922e0749e00c009