diff --git a/.github/workflows/test_environment.yml b/.github/workflows/test_environment.yml index 4a062f056844a..2d5d5205095e2 100644 --- a/.github/workflows/test_environment.yml +++ b/.github/workflows/test_environment.yml @@ -32,10 +32,10 @@ jobs: name: focal - os: ubuntu name: jammy - - os: ubuntu - name: lunar - os: ubuntu name: mantic + - os: ubuntu + name: noble - os: archlinux name: latest - os: debian diff --git a/AntennaTracker/ReleaseNotes.txt b/AntennaTracker/ReleaseNotes.txt index a8c64f03b5979..81f4a3a740c1d 100644 --- a/AntennaTracker/ReleaseNotes.txt +++ b/AntennaTracker/ReleaseNotes.txt @@ -1,4 +1,65 @@ Antenna Tracker Release Notes: +------------------------------ + +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 diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index 3c6398ec6a564..435134d6189e1 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -58,7 +58,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500, 40), SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45), SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50), - SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900, 55), #if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 300, 60), SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65), diff --git a/AntennaTracker/wscript b/AntennaTracker/wscript index cecd79a19a476..68ea44f0d1474 100644 --- a/AntennaTracker/wscript +++ b/AntennaTracker/wscript @@ -6,11 +6,7 @@ def build(bld): bld.ap_stlib( name=vehicle + '_libs', ap_vehicle=vehicle, - ap_libraries=bld.ap_common_vehicle_libraries() + [ - 'AP_Beacon', - 'AP_Arming', - 'AP_RCMapper', - ], + ap_libraries=bld.ap_common_vehicle_libraries(), ) bld.ap_program( diff --git a/ArduCopter/AP_ExternalControl_Copter.cpp b/ArduCopter/AP_ExternalControl_Copter.cpp index 35353a412618f..eb16147737fd6 100644 --- a/ArduCopter/AP_ExternalControl_Copter.cpp +++ b/ArduCopter/AP_ExternalControl_Copter.cpp @@ -29,6 +29,15 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f return true; } +bool AP_ExternalControl_Copter::set_global_position(const Location& loc) +{ + // Check if copter is ready for external control and returns false if it is not. + if (!ready_for_external_control()) { + return false; + } + return copter.set_target_location(loc); +} + bool AP_ExternalControl_Copter::ready_for_external_control() { return copter.flightmode->in_guided_mode() && copter.motors->armed(); diff --git a/ArduCopter/AP_ExternalControl_Copter.h b/ArduCopter/AP_ExternalControl_Copter.h index e7601c5552fc6..527af304f64a7 100644 --- a/ArduCopter/AP_ExternalControl_Copter.h +++ b/ArduCopter/AP_ExternalControl_Copter.h @@ -7,7 +7,8 @@ #if AP_EXTERNAL_CONTROL_ENABLED -class AP_ExternalControl_Copter : public AP_ExternalControl { +class AP_ExternalControl_Copter : public AP_ExternalControl +{ public: /* Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. @@ -15,6 +16,11 @@ class AP_ExternalControl_Copter : public AP_ExternalControl { Yaw is in earth frame, NED [rad/s]. */ bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override WARN_IF_UNUSED; + + /* + Sets the target global position for a loiter point. + */ + bool set_global_position(const Location& loc) override WARN_IF_UNUSED; private: /* Return true if Copter is ready to handle external control data. diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 0460de12ecf82..38aabd23dbf15 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -186,7 +186,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60), #endif - SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63), #if AC_PRECLAND_ENABLED SCHED_TASK(update_precland, 400, 50, 69), #endif @@ -273,32 +272,37 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, constexpr int8_t Copter::_failsafe_priorities[7]; -#if AP_SCRIPTING_ENABLED + +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED #if MODE_GUIDED_ENABLED == ENABLED -// start takeoff to given altitude (for use by scripting) -bool Copter::start_takeoff(float alt) +// set target location (for use by external control and scripting) +bool Copter::set_target_location(const Location& target_loc) { // exit if vehicle is not in Guided mode or Auto-Guided mode if (!flightmode->in_guided_mode()) { return false; } - if (mode_guided.do_user_takeoff_start(alt * 100.0f)) { - copter.set_auto_armed(true); - return true; - } - return false; + return mode_guided.set_destination(target_loc); } +#endif //MODE_GUIDED_ENABLED == ENABLED +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED -// set target location (for use by scripting) -bool Copter::set_target_location(const Location& target_loc) +#if AP_SCRIPTING_ENABLED +#if MODE_GUIDED_ENABLED == ENABLED +// start takeoff to given altitude (for use by scripting) +bool Copter::start_takeoff(float alt) { // exit if vehicle is not in Guided mode or Auto-Guided mode if (!flightmode->in_guided_mode()) { return false; } - return mode_guided.set_destination(target_loc); + if (mode_guided.do_user_takeoff_start(alt * 100.0f)) { + copter.set_auto_armed(true); + return true; + } + return false; } // set target position (for use by scripting) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3285f267976e5..a872dc67a2888 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -666,10 +666,15 @@ class Copter : public AP_Vehicle { void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override; +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if MODE_GUIDED_ENABLED == ENABLED + bool set_target_location(const Location& target_loc) override; +#endif // MODE_GUIDED_ENABLED == ENABLED +#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED + #if AP_SCRIPTING_ENABLED #if MODE_GUIDED_ENABLED == ENABLED bool start_takeoff(float alt) override; - bool set_target_location(const Location& target_loc) override; bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override; bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override; bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 402415038836b..b1eaaa0fdd020 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -836,6 +836,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i return MAV_RESULT_ACCEPTED; #if MODE_AUTO_ENABLED == ENABLED + case MAV_CMD_DO_RETURN_PATH_START: + if (copter.mode_auto.return_path_start_auto_RTL(ModeReason::GCS_COMMAND)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; + case MAV_CMD_DO_LAND_START: if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index faf5e4df70a75..b31c68b5c3e22 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,6 +1,77 @@ ArduPilot Copter Release Notes: ------------------------------- +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 + +------------------------------------------------------------------ +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 This release fixes a critical bug in the CRSF R/C protocol parser that diff --git a/ArduCopter/config.h b/ArduCopter/config.h index bd139ff23a58e..6a1ef097ed311 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -382,6 +382,9 @@ #ifndef LAND_DETECTOR_ACCEL_MAX # define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s #endif +#ifndef LAND_DETECTOR_VEL_Z_MAX +# define LAND_DETECTOR_VEL_Z_MAX 1.0f // vehicle vertical velocity must be under 1m/s +#endif ////////////////////////////////////////////////////////////////////////////// // Flight mode definitions diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index d7b82c497d203..c075e6c9b8958 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -100,11 +100,19 @@ void Copter::update_land_detector() } #endif + // check for aggressive flight requests - requested roll or pitch angle below 15 degrees + const Vector3f angle_target = attitude_control->get_att_target_euler_cd(); + bool large_angle_request = angle_target.xy().length() > LAND_CHECK_LARGE_ANGLE_CD; + + // check for large external disturbance - angle error over 30 degrees + const float angle_error = attitude_control->get_att_error_angle_deg(); + bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG); + // check that the airframe is not accelerating (not falling or braking after fast forward flight) bool accel_stationary = (land_accel_ef_filter.get().length() <= LAND_DETECTOR_ACCEL_MAX * land_detector_scalar); // check that vertical speed is within 1m/s of zero - bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100 * land_detector_scalar; + bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100.0 * LAND_DETECTOR_VEL_Z_MAX * land_detector_scalar; // if we have a healthy rangefinder only allow landing detection below 2 meters bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM); @@ -116,7 +124,7 @@ void Copter::update_land_detector() const bool WoW_check = true; #endif - if (motor_at_lower_limit && throttle_mix_at_min && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) { + if (motor_at_lower_limit && throttle_mix_at_min && !large_angle_request && !large_angle_error && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) { // landed criteria met - increment the counter and check if we've triggered if( land_detector_count < land_trigger_sec*scheduler.get_loop_rate_hz()) { land_detector_count++; diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index fe900d307db9a..c4e80689829b0 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -276,7 +276,8 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) #if MODE_AUTO_ENABLED == ENABLED if (mode == Mode::Number::AUTO_RTL) { // Special case for AUTO RTL, not a true mode, just AUTO in disguise - return mode_auto.jump_to_landing_sequence_auto_RTL(reason); + // Attempt to join return path, fallback to do-land-start + return mode_auto.return_path_or_jump_to_landing_sequence_auto_RTL(reason); } #endif @@ -972,19 +973,19 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms) switch (motors->get_spool_state()) { case AP_Motors::SpoolState::SHUT_DOWN: - return AltHold_MotorStopped; + return AltHoldModeState::MotorStopped; case AP_Motors::SpoolState::GROUND_IDLE: - return AltHold_Landed_Ground_Idle; + return AltHoldModeState::Landed_Ground_Idle; default: - return AltHold_Landed_Pre_Takeoff; + return AltHoldModeState::Landed_Pre_Takeoff; } } else if (takeoff.running() || takeoff.triggered(target_climb_rate_cms)) { // the aircraft is currently landed or taking off, asking for a positive climb rate and in THROTTLE_UNLIMITED // the aircraft should progress through the take off procedure - return AltHold_Takeoff; + return AltHoldModeState::Takeoff; } else if (!copter.ap.auto_armed || copter.ap.land_complete) { // the aircraft is armed and landed @@ -999,17 +1000,17 @@ Mode::AltHoldModeState Mode::get_alt_hold_state(float target_climb_rate_cms) if (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) { // the aircraft is waiting in ground idle - return AltHold_Landed_Ground_Idle; + return AltHoldModeState::Landed_Ground_Idle; } else { // the aircraft can leave the ground at any time - return AltHold_Landed_Pre_Takeoff; + return AltHoldModeState::Landed_Pre_Takeoff; } } else { // the aircraft is in a flying state motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - return AltHold_Flying; + return AltHoldModeState::Flying; } } diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index ad0618e45df13..928fadfe6fca0 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -3,6 +3,7 @@ #include "Copter.h" #include #include // TODO why is this needed if Copter.h includes this + class Parameters; class ParametersG2; @@ -231,12 +232,12 @@ class Mode { virtual float throttle_hover() const; // Alt_Hold based flight mode states used in Alt_Hold, Loiter, and Sport - enum AltHoldModeState { - AltHold_MotorStopped, - AltHold_Takeoff, - AltHold_Landed_Ground_Idle, - AltHold_Landed_Pre_Takeoff, - AltHold_Flying + enum class AltHoldModeState { + MotorStopped, + Takeoff, + Landed_Ground_Idle, + Landed_Pre_Takeoff, + Flying }; AltHoldModeState get_alt_hold_state(float target_climb_rate_cms); @@ -553,6 +554,12 @@ class ModeAuto : public Mode { // Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode bool jump_to_landing_sequence_auto_RTL(ModeReason reason); + // Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode + bool return_path_start_auto_RTL(ModeReason reason); + + // Try join return path else do land start + bool return_path_or_jump_to_landing_sequence_auto_RTL(ModeReason reason); + // lua accessors for nav script time support bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4); void nav_script_time_done(uint16_t id); @@ -589,6 +596,9 @@ class ModeAuto : public Mode { AllowWeatherVaning = (1 << 7U), }; + // Enter auto rtl pseudo mode + bool enter_auto_rtl(ModeReason reason); + bool start_command(const AP_Mission::Mission_Command& cmd); bool verify_command(const AP_Mission::Mission_Command& cmd); void exit_mission(); @@ -1622,22 +1632,29 @@ class ModeSystemId : public Mode { private: void log_data() const; + bool is_poscontrol_axis_type() const; enum class AxisType { - NONE = 0, // none - INPUT_ROLL = 1, // angle input roll axis is being excited - INPUT_PITCH = 2, // angle pitch axis is being excited - INPUT_YAW = 3, // angle yaw axis is being excited - RECOVER_ROLL = 4, // angle roll axis is being excited - RECOVER_PITCH = 5, // angle pitch axis is being excited - RECOVER_YAW = 6, // angle yaw axis is being excited - RATE_ROLL = 7, // rate roll axis is being excited - RATE_PITCH = 8, // rate pitch axis is being excited - RATE_YAW = 9, // rate yaw axis is being excited - MIX_ROLL = 10, // mixer roll axis is being excited - MIX_PITCH = 11, // mixer pitch axis is being excited - MIX_YAW = 12, // mixer pitch axis is being excited - MIX_THROTTLE = 13, // mixer throttle axis is being excited + NONE = 0, // none + INPUT_ROLL = 1, // angle input roll axis is being excited + INPUT_PITCH = 2, // angle pitch axis is being excited + INPUT_YAW = 3, // angle yaw axis is being excited + RECOVER_ROLL = 4, // angle roll axis is being excited + RECOVER_PITCH = 5, // angle pitch axis is being excited + RECOVER_YAW = 6, // angle yaw axis is being excited + RATE_ROLL = 7, // rate roll axis is being excited + RATE_PITCH = 8, // rate pitch axis is being excited + RATE_YAW = 9, // rate yaw axis is being excited + MIX_ROLL = 10, // mixer roll axis is being excited + MIX_PITCH = 11, // mixer pitch axis is being excited + MIX_YAW = 12, // mixer pitch axis is being excited + MIX_THROTTLE = 13, // mixer throttle axis is being excited + DISTURB_POS_LAT = 14, // lateral body axis measured position is being excited + DISTURB_POS_LONG = 15, // longitudinal body axis measured position is being excited + DISTURB_VEL_LAT = 16, // lateral body axis measured velocity is being excited + DISTURB_VEL_LONG = 17, // longitudinal body axis measured velocity is being excited + INPUT_VEL_LAT = 18, // lateral body axis commanded velocity is being excited + INPUT_VEL_LONG = 19, // longitudinal body axis commanded velocity is being excited }; AP_Int8 axis; // Controls which axis are being excited. Set to non-zero to display other parameters @@ -1654,7 +1671,9 @@ class ModeSystemId : public Mode { float waveform_freq_rads; // Instantaneous waveform frequency float time_const_freq; // Time at constant frequency before chirp starts int8_t log_subsample; // Subsample multiple for logging. - + Vector2f target_vel; // target velocity for position controller modes + Vector2f target_pos; // target positon + Vector2f input_vel_last; // last cycle input velocity // System ID states enum class SystemIDModeState { SYSTEMID_STATE_STOPPED, diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 03160ab2a0540..c1767407ce022 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -162,7 +162,7 @@ void ModeAcro::get_pilot_desired_angle_rates(float roll_in, float pitch_in, floa } // convert earth-frame level rates to body-frame level rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd() * radians(0.01f), rate_ef_level_cd, rate_bf_level_cd); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level_cd, rate_bf_level_cd); // combine earth frame rate corrections with rate requests if (g.acro_trainer == (uint8_t)Trainer::LIMITED) { diff --git a/ArduCopter/mode_acro_heli.cpp b/ArduCopter/mode_acro_heli.cpp index 17dc05bad264d..91259ce9756bc 100644 --- a/ArduCopter/mode_acro_heli.cpp +++ b/ArduCopter/mode_acro_heli.cpp @@ -144,7 +144,7 @@ void ModeAcro_Heli::virtual_flybar( float &roll_out, float &pitch_out, float &ya rate_ef_level.z = 0; // convert earth-frame leak rates to body-frame leak rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level); // combine earth frame rate corrections with rate requests roll_out += rate_bf_level.x; diff --git a/ArduCopter/mode_althold.cpp b/ArduCopter/mode_althold.cpp index 36c7a60143e3f..91c7943867d20 100644 --- a/ArduCopter/mode_althold.cpp +++ b/ArduCopter/mode_althold.cpp @@ -48,22 +48,22 @@ void ModeAltHold::run() // Alt Hold State Machine switch (althold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -76,7 +76,7 @@ void ModeAltHold::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); #if AP_AVOIDANCE_ENABLED diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index cd3060fa0f7fb..3733093544d96 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -164,7 +164,8 @@ void ModeAuto::run() } // only pretend to be in auto RTL so long as mission still thinks its in a landing sequence or the mission has completed - if (auto_RTL && (!(mission.get_in_landing_sequence_flag() || mission.state() == AP_Mission::mission_state::MISSION_COMPLETE))) { + const bool auto_rtl_active = mission.get_in_landing_sequence_flag() || mission.get_in_return_path_flag() || mission.state() == AP_Mission::mission_state::MISSION_COMPLETE; + if (auto_RTL && !auto_rtl_active) { auto_RTL = false; // log exit from Auto RTL #if HAL_LOGGING_ENABLED @@ -216,30 +217,75 @@ bool ModeAuto::allows_weathervaning() const // Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason) { - if (mission.jump_to_landing_sequence(get_stopping_point())) { - mission.set_force_resume(true); - // if not already in auto switch to auto - if ((copter.flightmode == &copter.mode_auto) || set_mode(Mode::Number::AUTO, reason)) { - auto_RTL = true; + if (!mission.jump_to_landing_sequence(get_stopping_point())) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + // make sad noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change_failed = 1; + } + gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No landing sequence found"); + return false; + } + + return enter_auto_rtl(reason); +} + +// Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode +bool ModeAuto::return_path_start_auto_RTL(ModeReason reason) +{ + if (!mission.jump_to_closest_mission_leg(get_stopping_point())) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + // make sad noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change_failed = 1; + } + gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No return path found"); + return false; + } + + return enter_auto_rtl(reason); +} + +// Try join return path else do land start +bool ModeAuto::return_path_or_jump_to_landing_sequence_auto_RTL(ModeReason reason) +{ + const Location stopping_point = get_stopping_point(); + if (!mission.jump_to_closest_mission_leg(stopping_point) && !mission.jump_to_landing_sequence(stopping_point)) { + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + // make sad noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change_failed = 1; + } + gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No return path or landing sequence found"); + return false; + } + + return enter_auto_rtl(reason); +} + +// Enter auto rtl pseudo mode +bool ModeAuto::enter_auto_rtl(ModeReason reason) +{ + mission.set_force_resume(true); + + // if not already in auto switch to auto + if ((copter.flightmode == this) || set_mode(Mode::Number::AUTO, reason)) { + auto_RTL = true; #if HAL_LOGGING_ENABLED - // log entry into AUTO RTL - copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), reason); + // log entry into AUTO RTL + copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), reason); #endif - // make happy noise - if (copter.ap.initialised) { - AP_Notify::events.user_mode_change = 1; - } - return true; + // make happy noise + if (copter.ap.initialised) { + AP_Notify::events.user_mode_change = 1; } - // mode change failed, revert force resume flag - mission.set_force_resume(false); - - gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed"); - } else { - gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No landing sequence found"); + return true; } + // mode change failed, revert force resume flag + mission.set_force_resume(false); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); // make sad noise if (copter.ap.initialised) { @@ -758,6 +804,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) break; #endif + case MAV_CMD_DO_RETURN_PATH_START: case MAV_CMD_DO_LAND_START: break; @@ -964,6 +1011,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) case MAV_CMD_DO_GUIDED_LIMITS: case MAV_CMD_DO_FENCE_ENABLE: case MAV_CMD_DO_WINCH: + case MAV_CMD_DO_RETURN_PATH_START: case MAV_CMD_DO_LAND_START: cmd_complete = true; break; diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index f5414e9dac29e..24ab8806be55a 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -263,7 +263,7 @@ void ModeFlowHold::run() // Flow Hold State Machine switch (flowhold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); copter.attitude_control->reset_rate_controller_I_terms(); copter.attitude_control->reset_yaw_target_and_rate(); @@ -271,7 +271,7 @@ void ModeFlowHold::run() flow_pi_xy.reset_I(); break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // set motors to full range copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); @@ -287,16 +287,16 @@ void ModeFlowHold::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Flying: + case AltHoldModeState::Flying: copter.motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index e52bfdae31012..d590b1125403d 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -960,8 +960,8 @@ void ModeGuided::angle_control_run() } // TODO: use get_alt_hold_state - // landed with positive desired climb rate, takeoff - if (copter.ap.land_complete && (guided_angle_state.climb_rate_cms > 0.0f)) { + // landed with positive desired climb rate or thrust, takeoff + if (copter.ap.land_complete && positive_thrust_or_climbrate) { zero_throttle_and_relax_ac(); motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index 602aa52859a15..1b76c414308cf 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -123,7 +123,7 @@ void ModeLoiter::run() // Loiter State Machine switch (loiter_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -131,18 +131,18 @@ void ModeLoiter::run() attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); loiter_nav->init_target(); attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -161,7 +161,7 @@ void ModeLoiter::run() attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false); break; - case AltHold_Flying: + case AltHoldModeState::Flying: // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index 7b47eeb7c3592..c90e36a18eaa5 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -100,7 +100,7 @@ void ModePosHold::run() // state machine switch (poshold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -115,14 +115,14 @@ void ModePosHold::run() init_wind_comp_estimate(); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); attitude_control->reset_yaw_target_and_rate(); init_wind_comp_estimate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -131,7 +131,7 @@ void ModePosHold::run() pitch_mode = RPMode::PILOT_OVERRIDE; break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -152,7 +152,7 @@ void ModePosHold::run() pitch_mode = RPMode::PILOT_OVERRIDE; break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate diff --git a/ArduCopter/mode_sport.cpp b/ArduCopter/mode_sport.cpp index 954a5a2b984d0..7647e4973c1f7 100644 --- a/ArduCopter/mode_sport.cpp +++ b/ArduCopter/mode_sport.cpp @@ -74,22 +74,22 @@ void ModeSport::run() // State Machine switch (sport_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -102,7 +102,7 @@ void ModeSport::run() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Flying: + case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 801f903205deb..d9869389ad3c4 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -1,4 +1,5 @@ #include "Copter.h" +#include #if MODE_SYSTEMID_ENABLED == ENABLED @@ -12,7 +13,7 @@ const AP_Param::GroupInfo ModeSystemId::var_info[] = { // @DisplayName: System identification axis // @Description: Controls which axis are being excited. Set to non-zero to see more parameters // @User: Standard - // @Values: 0:None, 1:Input Roll Angle, 2:Input Pitch Angle, 3:Input Yaw Angle, 4:Recovery Roll Angle, 5:Recovery Pitch Angle, 6:Recovery Yaw Angle, 7:Rate Roll, 8:Rate Pitch, 9:Rate Yaw, 10:Mixer Roll, 11:Mixer Pitch, 12:Mixer Yaw, 13:Mixer Thrust + // @Values: 0:None, 1:Input Roll Angle, 2:Input Pitch Angle, 3:Input Yaw Angle, 4:Recovery Roll Angle, 5:Recovery Pitch Angle, 6:Recovery Yaw Angle, 7:Rate Roll, 8:Rate Pitch, 9:Rate Yaw, 10:Mixer Roll, 11:Mixer Pitch, 12:Mixer Yaw, 13:Mixer Thrust, 14:Measured Lateral Position, 15:Measured Longitudinal Position, 16:Measured Lateral Velocity, 17:Measured Longitudinal Velocity, 18:Input Lateral Velocity, 19:Input Longitudinal Velocity AP_GROUPINFO_FLAGS("_AXIS", 1, ModeSystemId, axis, 0, AP_PARAM_FLAG_ENABLE), // @Param: _MAGNITUDE @@ -80,15 +81,58 @@ bool ModeSystemId::init(bool ignore_checks) return false; } - // if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high - if (motors->armed() && copter.ap.land_complete && !copter.flightmode->has_manual_throttle()) { + // ensure we are flying + if (!copter.motors->armed() || !copter.ap.auto_armed || copter.ap.land_complete) { + gcs().send_text(MAV_SEVERITY_WARNING, "Aircraft must be flying"); return false; } + if (!is_poscontrol_axis_type()) { + + // System ID is being done on the attitude control loops + + // Can only switch into System ID Axes 1-13 with a flight mode that has manual throttle + if (!copter.flightmode->has_manual_throttle()) { + gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires manual throttle"); + return false; + } + #if FRAME_CONFIG == HELI_FRAME - copter.input_manager.set_use_stab_col(true); + copter.input_manager.set_use_stab_col(true); #endif + } else { + + // System ID is being done on the position control loops + + // Can only switch into System ID Axes 14-19 from Loiter flight mode + if (copter.flightmode->mode_number() != Mode::Number::LOITER) { + gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires switch from Loiter"); + return false; + } + + // set horizontal speed and acceleration limits + pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration()); + + // initialise the horizontal position controller + if (!pos_control->is_active_xy()) { + pos_control->init_xy_controller(); + } + + // set vertical speed and acceleration limits + pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z()); + + // initialise the vertical position controller + if (!pos_control->is_active_z()) { + pos_control->init_z_controller(); + } + Vector3f curr_pos; + curr_pos = inertial_nav.get_position_neu_cm(); + target_pos = curr_pos.xy(); + } + att_bf_feedforward = attitude_control->get_bf_feedforward(); waveform_time = 0.0f; time_const_freq = 2.0f / frequency_start; // Two full cycles at the starting frequency @@ -117,65 +161,74 @@ void ModeSystemId::exit() // should be called at 100hz or more void ModeSystemId::run() { - // apply simple mode transform to pilot inputs - update_simple_mode(); - - // convert pilot input to lean angles float target_roll, target_pitch; - get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max); - - // get pilot's desired yaw rate - float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); - - if (!motors->armed()) { - // Motors should be Stopped - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); - // Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when - // motor interlock is disabled. - } else if (copter.ap.throttle_zero && !copter.is_tradheli()) { - // Attempting to Land - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); - } else { - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - } + float target_yaw_rate = 0.0f; + float pilot_throttle_scaled = 0.0f; + float target_climb_rate = 0.0f; + Vector2f input_vel; + + if (!is_poscontrol_axis_type()) { + + // apply simple mode transform to pilot inputs + update_simple_mode(); + + // convert pilot input to lean angles + get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max); + + // get pilot's desired yaw rate + target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz()); + + if (!motors->armed()) { + // Motors should be Stopped + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN); + // Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when + // motor interlock is disabled. + } else if (copter.ap.throttle_zero && !copter.is_tradheli()) { + // Attempting to Land + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE); + } else { + motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); + } - switch (motors->get_spool_state()) { - case AP_Motors::SpoolState::SHUT_DOWN: - // Motors Stopped - attitude_control->reset_yaw_target_and_rate(); - attitude_control->reset_rate_controller_I_terms(); - break; - - case AP_Motors::SpoolState::GROUND_IDLE: - // Landed - // Tradheli initializes targets when going from disarmed to armed state. - // init_targets_on_arming is always set true for multicopter. - if (motors->init_targets_on_arming()) { + switch (motors->get_spool_state()) { + case AP_Motors::SpoolState::SHUT_DOWN: + // Motors Stopped attitude_control->reset_yaw_target_and_rate(); - attitude_control->reset_rate_controller_I_terms_smoothly(); - } - break; + attitude_control->reset_rate_controller_I_terms(); + break; - case AP_Motors::SpoolState::THROTTLE_UNLIMITED: - // clear landing flag above zero throttle - if (!motors->limit.throttle_lower) { - set_land_complete(false); - } - break; + case AP_Motors::SpoolState::GROUND_IDLE: + // Landed + // Tradheli initializes targets when going from disarmed to armed state. + // init_targets_on_arming is always set true for multicopter. + if (motors->init_targets_on_arming()) { + attitude_control->reset_yaw_target_and_rate(); + attitude_control->reset_rate_controller_I_terms_smoothly(); + } + break; - case AP_Motors::SpoolState::SPOOLING_UP: - case AP_Motors::SpoolState::SPOOLING_DOWN: - // do nothing - break; - } + case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + // clear landing flag above zero throttle + if (!motors->limit.throttle_lower) { + set_land_complete(false); + } + break; + + case AP_Motors::SpoolState::SPOOLING_UP: + case AP_Motors::SpoolState::SPOOLING_DOWN: + // do nothing + break; + } - // get pilot's desired throttle + // get pilot's desired throttle #if FRAME_CONFIG == HELI_FRAME - float pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); + pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); #else - float pilot_throttle_scaled = get_pilot_desired_throttle(); + pilot_throttle_scaled = get_pilot_desired_throttle(); #endif + } + if ((systemid_state == SystemIDModeState::SYSTEMID_STATE_TESTING) && (!is_positive(frequency_start) || !is_positive(frequency_stop) || is_negative(time_fade_in) || !is_positive(time_record) || is_negative(time_fade_out) || (time_record <= time_const_freq))) { systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED; @@ -185,7 +238,7 @@ void ModeSystemId::run() waveform_time += G_Dt; waveform_sample = chirp_input.update(waveform_time - SYSTEM_ID_DELAY, waveform_magnitude); waveform_freq_rads = chirp_input.get_frequency_rads(); - + Vector2f disturb_state; switch (systemid_state) { case SystemIDModeState::SYSTEMID_STATE_STOPPED: attitude_control->bf_feedforward(att_bf_feedforward); @@ -255,15 +308,79 @@ void ModeSystemId::run() case AxisType::MIX_THROTTLE: pilot_throttle_scaled += waveform_sample; break; + case AxisType::DISTURB_POS_LAT: + disturb_state.x = 0.0f; + disturb_state.y = waveform_sample * 100.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_pos_cm(disturb_state); + break; + case AxisType::DISTURB_POS_LONG: + disturb_state.x = waveform_sample * 100.0f; + disturb_state.y = 0.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_pos_cm(disturb_state); + break; + case AxisType::DISTURB_VEL_LAT: + disturb_state.x = 0.0f; + disturb_state.y = waveform_sample * 100.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_vel_cms(disturb_state); + break; + case AxisType::DISTURB_VEL_LONG: + disturb_state.x = waveform_sample * 100.0f; + disturb_state.y = 0.0f; + disturb_state.rotate(attitude_control->get_att_target_euler_rad().z); + pos_control->set_disturb_vel_cms(disturb_state); + break; + case AxisType::INPUT_VEL_LAT: + input_vel.x = 0.0f; + input_vel.y = waveform_sample * 100.0f; + input_vel.rotate(attitude_control->get_att_target_euler_rad().z); + break; + case AxisType::INPUT_VEL_LONG: + input_vel.x = waveform_sample * 100.0f; + input_vel.y = 0.0f; + input_vel.rotate(attitude_control->get_att_target_euler_rad().z); + break; } break; } - // call attitude controller - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); + if (!is_poscontrol_axis_type()) { + + // call attitude controller + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); + + // output pilot's throttle + attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt); + + } else { + + // relax loiter target if we might be landed + if (copter.ap.land_complete_maybe) { + pos_control->soften_for_landing_xy(); + } - // output pilot's throttle - attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt); + Vector2f accel; + target_pos += input_vel * G_Dt; + if (is_positive(G_Dt)) { + accel = (input_vel - input_vel_last) / G_Dt; + input_vel_last = input_vel; + } + pos_control->set_pos_vel_accel_xy(target_pos.topostype(), input_vel, accel); + + // run pos controller + pos_control->update_xy_controller(); + + // call attitude controller + attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), target_yaw_rate, false); + + // Send the commanded climb rate to the position controller + pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); + + // run the vertical position controller and set output throttle + pos_control->update_z_controller(); + } if (log_subsample <= 0) { log_data(); @@ -298,6 +415,33 @@ void ModeSystemId::log_data() const // Full rate logging of attitude, rate and pid loops copter.Log_Write_Attitude(); copter.Log_Write_PIDS(); + + if (is_poscontrol_axis_type()) { + pos_control->write_log(); + copter.logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x()); + copter.logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y()); + + } +} + +bool ModeSystemId::is_poscontrol_axis_type() const +{ + bool ret = false; + + switch ((AxisType)axis.get()) { + case AxisType::DISTURB_POS_LAT: + case AxisType::DISTURB_POS_LONG: + case AxisType::DISTURB_VEL_LAT: + case AxisType::DISTURB_VEL_LONG: + case AxisType::INPUT_VEL_LAT: + case AxisType::INPUT_VEL_LONG: + ret = true; + break; + default: + break; + } + + return ret; } #endif diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index 6847126f36434..3887f1bd52714 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -326,7 +326,7 @@ void ModeZigZag::manual_control() // althold state machine switch (althold_state) { - case AltHold_MotorStopped: + case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero @@ -334,7 +334,7 @@ void ModeZigZag::manual_control() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate); break; - case AltHold_Takeoff: + case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); @@ -353,18 +353,18 @@ void ModeZigZag::manual_control() takeoff.do_pilot_takeoff(target_climb_rate); break; - case AltHold_Landed_Ground_Idle: + case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; - case AltHold_Landed_Pre_Takeoff: + case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); loiter_nav->init_target(); attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; - case AltHold_Flying: + case AltHoldModeState::Flying: // set motors to full range motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index c1cea4d4cc332..ee5c7f9f334d9 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -956,7 +956,7 @@ void ToyMode::handle_message(const mavlink_message_t &msg) // immediately update AP_Notify recording flag AP_Notify::flags.video_recording = true; } else if (strncmp(m.name, "WIFICHAN", 10) == 0) { -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED AP_Radio *radio = AP_Radio::get_singleton(); if (radio) { radio->set_wifi_channel(m.value); diff --git a/ArduCopter/wscript b/ArduCopter/wscript index 677477922a23d..13bde3905e896 100644 --- a/ArduCopter/wscript +++ b/ArduCopter/wscript @@ -17,12 +17,9 @@ def build(bld): 'AP_IRLock', 'AP_InertialNav', 'AP_Motors', - 'AP_RCMapper', 'AP_Avoidance', 'AP_AdvancedFailsafe', 'AP_SmartRTL', - 'AP_Beacon', - 'AP_Arming', 'AP_WheelEncoder', 'AP_Winch', 'AP_Follow', diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 061cb476a07bd..a774b778f5f59 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -214,7 +214,7 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) Q_ASSIST_SPEED really should be enabled for all quadplanes except tailsitters */ if (check_enabled(ARMING_CHECK_PARAMETERS) && - is_zero(plane.quadplane.assist_speed) && + is_zero(plane.quadplane.assist.speed) && !plane.quadplane.tailsitter.enabled()) { check_failed(display_failure,"Q_ASSIST_SPEED is not set"); ret = false; diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 3a9dc4f70a735..59e65dc343e73 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -81,7 +81,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63), #endif SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66), - SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150, 69), SCHED_TASK(read_rangefinder, 50, 100, 78), #if AP_ICENGINE_ENABLED SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81), diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index aabe9cfbe536d..8ffa3f82972e8 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -234,7 +234,7 @@ void GCS_MAVLINK_Plane::send_nav_controller_output() const nav_controller->nav_bearing_cd() * 0.01, nav_controller->target_bearing_cd() * 0.01, MIN(plane.auto_state.wp_distance, UINT16_MAX), - plane.altitude_error_cm * 0.01, + plane.calc_altitude_error_cm() * 0.01, plane.airspeed_error * 100, // incorrect units; see PR#7933 nav_controller->crosstrack_error()); } @@ -1463,7 +1463,7 @@ int16_t GCS_MAVLINK_Plane::high_latency_target_altitude() const return (plane.control_mode != &plane.mode_qstabilize) ? 0.01 * (global_position_current.alt + quadplane.pos_control->get_pos_error_z_cm()) : 0; } #endif - return 0.01 * (global_position_current.alt + plane.altitude_error_cm); + return 0.01 * (global_position_current.alt + plane.calc_altitude_error_cm()); } uint8_t GCS_MAVLINK_Plane::high_latency_tgt_heading() const diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index c712b2db1756b..2eac3ece63157 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -178,7 +178,7 @@ void Plane::Log_Write_Nav_Tuning() wp_distance : auto_state.wp_distance, target_bearing_cd : (int16_t)nav_controller->target_bearing_cd(), nav_bearing_cd : (int16_t)nav_controller->nav_bearing_cd(), - altitude_error_cm : (int16_t)altitude_error_cm, + altitude_error_cm : (int16_t)plane.calc_altitude_error_cm(), xtrack_error : nav_controller->crosstrack_error(), xtrack_error_i : nav_controller->crosstrack_error_integrator(), airspeed_error : airspeed_error, @@ -389,7 +389,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: CRt: climb rate // @Field: TMix: transition throttle mix value // @Field: Trn: Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done -// @Field: Ast: Q assist active +// @Field: Ast: bitmask of assistance flags +// @FieldBitmaskEnum: Ast: log_assistance_flags #if HAL_QUADPLANE_ENABLED { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), "QTUN", "QffffffeccfBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Trn,Ast", "s----mmmnn---", "F----00000---" , true }, @@ -438,6 +439,17 @@ const struct LogStructure Plane::log_structure[] = { "TSIT", "Qfff", "TimeUS,Ts,Ss,Tmin", "s---", "F---" , true }, #endif +// @LoggerMessage: TILT +// @Description: Tiltrotor tilt values +// @Field: TimeUS: Time since system startup +// @Field: Tilt: Current tilt angle, 0 deg vertical, 90 deg horizontal +// @Field: FL: Front left tilt angle, 0 deg vertical, 90 deg horizontal +// @Field: FR: Front right tilt angle, 0 deg vertical, 90 deg horizontal +#if HAL_QUADPLANE_ENABLED + { LOG_TILT_MSG, sizeof(Tiltrotor::log_tiltrotor), + "TILT", "Qfff", "TimeUS,Tilt,FL,FR", "sddd", "F---" , true }, +#endif + // @LoggerMessage: PIDG // @Description: Plane Proportional/Integral/Derivative gain values for Heading when using COMMAND_INT control. // @Field: TimeUS: Time since system startup diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 419283a14fd49..6fa9ebc97ef05 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -517,7 +517,7 @@ const AP_Param::Info Plane::var_info[] = { // @Description: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls. // @Units: deg // @Range: 0 90 - // @Increment: 0.1 + // @Increment: 1 // @User: Standard ASCALAR(roll_limit, "ROLL_LIMIT_DEG", ROLL_LIMIT_DEG), @@ -526,7 +526,7 @@ const AP_Param::Info Plane::var_info[] = { // @Description: Maximum pitch up angle commanded in modes with stabilized limits. // @Units: deg // @Range: 0 90 - // @Increment: 10 + // @Increment: 1 // @User: Standard ASCALAR(pitch_limit_max, "PTCH_LIM_MAX_DEG", PITCH_MAX), @@ -535,7 +535,7 @@ const AP_Param::Info Plane::var_info[] = { // @Description: Maximum pitch down angle commanded in modes with stabilized limits // @Units: deg // @Range: -90 0 - // @Increment: 10 + // @Increment: 1 // @User: Standard ASCALAR(pitch_limit_min, "PTCH_LIM_MIN_DEG", PITCH_MIN), diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 71b450256c4d9..613cc25a9b248 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -143,6 +143,7 @@ class Plane : public AP_Vehicle { friend class Tiltrotor; friend class SLT_Transition; friend class Tailsitter_Transition; + friend class VTOL_Assist; friend class Mode; friend class ModeCircle; @@ -399,9 +400,6 @@ class Plane : public AP_Vehicle { int32_t groundspeed_undershoot; bool groundspeed_undershoot_is_valid; - // Difference between current altitude and desired altitude. Centimeters - int32_t altitude_error_cm; - // speed scaler for control surfaces, updated at 10Hz float surface_speed_scaler = 1.0; @@ -479,10 +477,6 @@ class Plane : public AP_Vehicle { // Minimum pitch to hold during takeoff command execution. Hundredths of a degree int16_t takeoff_pitch_cd; - // used to 'wiggle' servos in idle mode to prevent them freezing - // at high altitudes - uint8_t idle_wiggle_stage; - // Flag for using gps ground course instead of INS yaw. Set false when takeoff command in process. bool takeoff_complete; @@ -1085,13 +1079,12 @@ class Plane : public AP_Vehicle { // system.cpp void init_ardupilot() override; - void startup_ground(void); bool set_mode(Mode& new_mode, const ModeReason reason); bool set_mode(const uint8_t mode, const ModeReason reason) override; bool set_mode_by_number(const Mode::Number new_mode_number, const ModeReason reason); void check_long_failsafe(); void check_short_failsafe(); - void startup_INS_ground(void); + void startup_INS(void); bool should_log(uint32_t mask); int8_t throttle_percentage(void); void notify_mode(const Mode& mode); @@ -1110,7 +1103,6 @@ class Plane : public AP_Vehicle { void avoidance_adsb_update(void); // servos.cpp - void set_servos_idle(void); void set_servos(); float apply_throttle_limits(float throttle_in); void set_throttle(void); diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 1fc5b0ad222a1..338e5582c8781 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -61,17 +61,17 @@ void RC_Channel_Plane::do_aux_function_q_assist_state(AuxSwitchPos ch_flag) switch(ch_flag) { case AuxSwitchPos::HIGH: gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Force enabled"); - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE); + plane.quadplane.assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED); break; case AuxSwitchPos::MIDDLE: gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Enabled"); - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED); + plane.quadplane.assist.set_state(VTOL_Assist::STATE::ASSIST_ENABLED); break; case AuxSwitchPos::LOW: gcs().send_text(MAV_SEVERITY_INFO, "QAssist: Disabled"); - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED); + plane.quadplane.assist.set_state(VTOL_Assist::STATE::ASSIST_DISABLED); break; } } @@ -121,20 +121,11 @@ void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag) switch(ch_flag) { case AuxSwitchPos::HIGH: plane.flare_mode = Plane::FlareMode::ENABLED_PITCH_TARGET; -#if HAL_QUADPLANE_ENABLED - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED); -#endif break; case AuxSwitchPos::MIDDLE: plane.flare_mode = Plane::FlareMode::ENABLED_NO_PITCH_TARGET; -#if HAL_QUADPLANE_ENABLED - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED); -#endif break; case AuxSwitchPos::LOW: -#if HAL_QUADPLANE_ENABLED - plane.quadplane.set_q_assist_state(plane.quadplane.Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED); -#endif plane.flare_mode = Plane::FlareMode::FLARE_DISABLED; break; } diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index f83e0cf44e9db..db75731037339 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,3 +1,76 @@ +ArduPilot Plane Release Notes: +------------------------------ + +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/VTOL_Assist.cpp b/ArduPlane/VTOL_Assist.cpp new file mode 100644 index 0000000000000..f071b5865d49b --- /dev/null +++ b/ArduPlane/VTOL_Assist.cpp @@ -0,0 +1,143 @@ +#include "Plane.h" + +#if HAL_QUADPLANE_ENABLED + +// Assistance hysteresis helpers + +// Reset state +void VTOL_Assist::Assist_Hysteresis::reset() +{ + start_ms = 0; + last_ms = 0; + active = false; +} + +// Update state, return true when first triggered +bool VTOL_Assist::Assist_Hysteresis::update(const bool trigger, const uint32_t &now_ms, const uint32_t &trigger_delay_ms, const uint32_t &clear_delay_ms) +{ + bool ret = false; + + if (trigger) { + last_ms = now_ms; + if (start_ms == 0) { + start_ms = now_ms; + } + if ((now_ms - start_ms) > trigger_delay_ms) { + // trigger delay has elapsed + if (!active) { + // return true on first trigger + ret = true; + } + active = true; + } + + } else if (active) { + if ((last_ms == 0) || ((now_ms - last_ms) > clear_delay_ms)) { + // Clear delay passed + reset(); + } + + } else { + reset(); + } + + return ret; +} + +// Assistance not needed, reset any state +void VTOL_Assist::reset() +{ + force_assist = false; + speed_assist = false; + angle_error.reset(); + alt_error.reset(); +} + +/* + return true if the quadplane should provide stability assistance + */ +bool VTOL_Assist::should_assist(float aspeed, bool have_airspeed) +{ + if (!plane.arming.is_armed_and_safety_off() || (state == STATE::ASSIST_DISABLED) || quadplane.tailsitter.is_control_surface_tailsitter()) { + // disarmed or disabled by aux switch or because a control surface tailsitter + reset(); + return false; + } + + if (!quadplane.tailsitter.enabled() && !( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) + || is_positive(plane.get_throttle_input()) + || plane.is_flying() ) ) { + // not in a flight mode and condition where it would be safe to turn on vertial lift motors + // skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes + reset(); + return false; + } + + if (plane.flare_mode != Plane::FlareMode::FLARE_DISABLED) { + // Never active in fixed wing flare + reset(); + return false; + } + + force_assist = state == STATE::FORCE_ENABLED; + + if (speed <= 0) { + // all checks disabled via speed threshold, still allow force enabled + speed_assist = false; + alt_error.reset(); + angle_error.reset(); + return force_assist; + } + + // assistance due to Q_ASSIST_SPEED + // if option bit is enabled only allow assist with real airspeed sensor + speed_assist = (have_airspeed && aspeed < speed) && + (!quadplane.option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || plane.ahrs.using_airspeed_sensor()); + + const uint32_t now_ms = AP_HAL::millis(); + const uint32_t tigger_delay_ms = delay * 1000; + const uint32_t clear_delay_ms = tigger_delay_ms * 2; + + /* + optional assistance when altitude is too close to the ground + */ + if (alt <= 0) { + // Alt assist disabled + alt_error.reset(); + + } else { + const float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); + if (alt_error.update(height_above_ground < alt, now_ms, tigger_delay_ms, clear_delay_ms)) { + gcs().send_text(MAV_SEVERITY_WARNING, "Alt assist %.1fm", height_above_ground); + } + } + + if (angle <= 0) { + // Angle assist disabled + angle_error.reset(); + + } else { + + /* + now check if we should provide assistance due to attitude error + */ + const uint16_t allowed_envelope_error_cd = 500U; + const bool inside_envelope = (labs(plane.ahrs.roll_sensor) <= (plane.aparm.roll_limit*100 + allowed_envelope_error_cd)) && + (plane.ahrs.pitch_sensor < (plane.aparm.pitch_limit_max*100 + allowed_envelope_error_cd)) && + (plane.ahrs.pitch_sensor > (plane.aparm.pitch_limit_min*100 - allowed_envelope_error_cd)); + + const int32_t max_angle_cd = 100U*angle; + const bool inside_angle_error = (labs(plane.ahrs.roll_sensor - plane.nav_roll_cd) < max_angle_cd) && + (labs(plane.ahrs.pitch_sensor - plane.nav_pitch_cd) < max_angle_cd); + + if (angle_error.update(!inside_envelope && !inside_angle_error, now_ms, tigger_delay_ms, clear_delay_ms)) { + gcs().send_text(MAV_SEVERITY_WARNING, "Angle assist r=%d p=%d", + (int)(plane.ahrs.roll_sensor/100), + (int)(plane.ahrs.pitch_sensor/100)); + } + } + + return force_assist || speed_assist || alt_error.is_active() || angle_error.is_active(); +} + +#endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/VTOL_Assist.h b/ArduPlane/VTOL_Assist.h new file mode 100644 index 0000000000000..c358223650173 --- /dev/null +++ b/ArduPlane/VTOL_Assist.h @@ -0,0 +1,72 @@ +#pragma once + +// VTOL assistance in a forward flight mode + +class QuadPlane; +class VTOL_Assist { +public: + VTOL_Assist(QuadPlane& _quadplane):quadplane(_quadplane) {}; + + // check for assistance needed + bool should_assist(float aspeed, bool have_airspeed); + + // Assistance not needed, reset any state + void reset(); + + // speed below which quad assistance is given + AP_Float speed; + + // angular error at which quad assistance is given + AP_Int8 angle; + + // altitude to trigger assistance + AP_Int16 alt; + + // Time hysteresis for triggering of assistance + AP_Float delay; + + // State from pilot + enum class STATE { + ASSIST_DISABLED, + ASSIST_ENABLED, + FORCE_ENABLED, + }; + void set_state(STATE _state) { state = _state; } + + // Logging getters for assist types + bool in_force_assist() const { return force_assist; } + bool in_speed_assist() const { return speed_assist; } + bool in_alt_assist() const { return alt_error.is_active(); } + bool in_angle_assist() const { return angle_error.is_active(); } + +private: + + // Default to enabled + STATE state = STATE::ASSIST_ENABLED; + + class Assist_Hysteresis { + public: + // Reset state + void reset(); + + // Update state, return true when first triggered + bool update(const bool trigger, const uint32_t &now_ms, const uint32_t &trigger_delay_ms, const uint32_t &clear_delay_ms); + + // Return true if the output is active + bool is_active() const { return active; } + + private: + uint32_t start_ms; + uint32_t last_ms; + bool active; + }; + Assist_Hysteresis angle_error; + Assist_Hysteresis alt_error; + + // Force and speed assist have no hysteresis + bool force_assist; + bool speed_assist; + + // Reference to access quadplane + QuadPlane& quadplane; +}; diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 215b4cf05e20d..728ff97ad9af4 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -284,7 +284,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret return verify_continue_and_change_alt(); case MAV_CMD_NAV_ALTITUDE_WAIT: - return verify_altitude_wait(cmd); + return mode_auto.verify_altitude_wait(cmd); #if HAL_QUADPLANE_ENABLED case MAV_CMD_NAV_VTOL_TAKEOFF: @@ -350,7 +350,6 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm) next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm); setup_terrain_target_alt(next_WP_loc); set_target_altitude_location(next_WP_loc); - plane.altitude_error_cm = calc_altitude_error_cm(); if (aparm.loiter_radius < 0) { loiter.direction = -1; @@ -845,26 +844,25 @@ bool Plane::verify_continue_and_change_alt() /* see if we have reached altitude or descent speed */ -bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd) +bool ModeAuto::verify_altitude_wait(const AP_Mission::Mission_Command &cmd) { - if (current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) { + if (plane.current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) { gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude"); return true; } - if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) { - gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)auto_state.sink_rate); + if (plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) { + gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)plane.auto_state.sink_rate); return true; } // if requested, wiggle servos if (cmd.content.altitude_wait.wiggle_time != 0) { - static uint32_t last_wiggle_ms; - if (auto_state.idle_wiggle_stage == 0 && - AP_HAL::millis() - last_wiggle_ms > cmd.content.altitude_wait.wiggle_time*1000) { - auto_state.idle_wiggle_stage = 1; - last_wiggle_ms = AP_HAL::millis(); + if (wiggle.stage == 0 && + AP_HAL::millis() - wiggle.last_ms > cmd.content.altitude_wait.wiggle_time*1000) { + wiggle.stage = 1; + wiggle.last_ms = AP_HAL::millis(); + // idle_wiggle_stage is updated in wiggle_servos() } - // idle_wiggle_stage is updated in set_servos_idle() } return false; diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index fac041ad667e4..f4a8f9fc45111 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -103,6 +103,7 @@ enum log_messages { LOG_AETR_MSG, LOG_OFG_MSG, LOG_TSIT_MSG, + LOG_TILT_MSG, }; #define MASK_LOG_ATTITUDE_FAST (1<<0) diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index 30ec5fc5b0fb1..0a4415ff8b65a 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -191,8 +191,6 @@ void Mode::update_target_altitude() } else { plane.set_target_altitude_location(plane.next_WP_loc); } - - plane.altitude_error_cm = plane.calc_altitude_error_cm(); } // returns true if the vehicle can be armed in this mode diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index a217c2bf7d8e1..cfe306813b31c 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -233,6 +233,8 @@ class ModeAuto : public Mode void do_nav_delay(const AP_Mission::Mission_Command& cmd); bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); + bool verify_altitude_wait(const AP_Mission::Mission_Command& cmd); + void run() override; protected: @@ -249,6 +251,12 @@ class ModeAuto : public Mode uint32_t time_start_ms; } nav_delay; + // wiggle state and timer for NAV_ALTITUDE_WAIT + void wiggle_servos(); + struct { + uint8_t stage; + uint32_t last_ms; + } wiggle; }; diff --git a/ArduPlane/mode_auto.cpp b/ArduPlane/mode_auto.cpp index 73753e1fa44ca..3153d7de31e06 100644 --- a/ArduPlane/mode_auto.cpp +++ b/ArduPlane/mode_auto.cpp @@ -167,8 +167,16 @@ bool ModeAuto::is_landing() const void ModeAuto::run() { if (plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT) { - // Wiggle servos - plane.set_servos_idle(); + + wiggle_servos(); + + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); + + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight); // Relax attitude control reset_controllers(); diff --git a/ArduPlane/mode_guided.cpp b/ArduPlane/mode_guided.cpp index 85462166d1bc7..86a3bf60c1aee 100644 --- a/ArduPlane/mode_guided.cpp +++ b/ArduPlane/mode_guided.cpp @@ -147,7 +147,6 @@ void ModeGuided::update_target_altitude() } plane.guided_state.last_target_alt = temp.alt; plane.set_target_altitude_location(temp); - plane.altitude_error_cm = plane.calc_altitude_error_cm(); } else #endif // OFFBOARD_GUIDED == ENABLED { diff --git a/ArduPlane/mode_qrtl.cpp b/ArduPlane/mode_qrtl.cpp index 7de44dbc9e030..87c3b7712874b 100644 --- a/ArduPlane/mode_qrtl.cpp +++ b/ArduPlane/mode_qrtl.cpp @@ -211,7 +211,6 @@ void ModeQRTL::update_target_altitude() Location loc = plane.next_WP_loc; loc.alt += alt*100; plane.set_target_altitude_location(loc); - plane.altitude_error_cm = plane.calc_altitude_error_cm(); } // only nudge during approach diff --git a/ArduPlane/mode_rtl.cpp b/ArduPlane/mode_rtl.cpp index c35a3b64a6abd..15d9728006f5b 100644 --- a/ArduPlane/mode_rtl.cpp +++ b/ArduPlane/mode_rtl.cpp @@ -106,7 +106,7 @@ void ModeRTL::navigate() if ((plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) || (plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START && plane.reached_loiter_target() && - labs(plane.altitude_error_cm) < 1000)) + labs(plane.calc_altitude_error_cm()) < 1000)) { // we've reached the RTL point, see if we have a landing sequence if (plane.have_position && plane.mission.jump_to_landing_sequence(plane.current_loc)) { diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 3abf8a58becef..6a7896587114c 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -401,7 +401,10 @@ void Plane::update_fbwb_speed_height(void) set_target_altitude_current(); } - int32_t alt_change_cm = g.flybywire_climb_rate * elevator_input * dt * 100; + float climb_rate = g.flybywire_climb_rate * elevator_input; + climb_rate = constrain_float(climb_rate, -TECS_controller.get_max_sinkrate(), TECS_controller.get_max_climbrate()); + + int32_t alt_change_cm = climb_rate * dt * 100; change_target_altitude(alt_change_cm); #if HAL_SOARING_ENABLED @@ -422,8 +425,6 @@ void Plane::update_fbwb_speed_height(void) check_fbwb_altitude(); - altitude_error_cm = calc_altitude_error_cm(); - calc_throttle(); calc_nav_pitch(); } diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index a96d70aeb50f8..7217486133bbe 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -108,7 +108,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Range: 0 100 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("ASSIST_SPEED", 24, QuadPlane, assist_speed, 0), + AP_GROUPINFO("ASSIST_SPEED", 24, QuadPlane, assist.speed, 0), // @Param: YAW_RATE_MAX // @DisplayName: Maximum yaw rate @@ -236,7 +236,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Range: 0 90 // @Increment: 1 // @User: Standard - AP_GROUPINFO("ASSIST_ANGLE", 45, QuadPlane, assist_angle, 30), + AP_GROUPINFO("ASSIST_ANGLE", 45, QuadPlane, assist.angle, 30), // 47: TILT_TYPE // 48: TAILSIT_ANGLE @@ -310,7 +310,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Param: TRIM_PITCH // @DisplayName: Quadplane AHRS trim pitch - // @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes TRIM_PITCH. For tailsitters, this is relative to a baseline of 90 degrees in AHRS. + // @Description: This sets the compensation for the pitch angle trim difference between calibrated AHRS level and vertical flight pitch. NOTE! this is relative to calibrated AHRS trim, not forward flight trim which includes PTCH_TRIM_DEG. For tailsitters, this is relative to a baseline of 90 degrees in AHRS. // @Units: deg // @Range: -10 +10 // @Increment: 0.1 @@ -405,7 +405,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Range: 0 120 // @Increment: 1 // @User: Standard - AP_GROUPINFO("ASSIST_ALT", 16, QuadPlane, assist_alt, 0), + AP_GROUPINFO("ASSIST_ALT", 16, QuadPlane, assist.alt, 0), // 17: TAILSIT_GSCMSK // 18: TAILSIT_GSCMIN @@ -417,7 +417,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Range: 0 2 // @Increment: 0.1 // @User: Standard - AP_GROUPINFO("ASSIST_DELAY", 19, QuadPlane, assist_delay, 0.5), + AP_GROUPINFO("ASSIST_DELAY", 19, QuadPlane, assist.delay, 0.5), // @Param: FWD_MANTHR_MAX // @DisplayName: VTOL manual forward throttle max percent @@ -825,7 +825,7 @@ bool QuadPlane::setup(void) // default QAssist state as set with Q_OPTIONS if (option_is_set(QuadPlane::OPTION::Q_ASSIST_FORCE_ENABLE)) { - q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; + assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED); } setup_defaults(); @@ -1417,7 +1417,7 @@ float QuadPlane::assist_climb_rate_cms(void) const float climb_rate; if (plane.control_mode->does_auto_throttle()) { // use altitude_error_cm, spread over 10s interval - climb_rate = plane.altitude_error_cm * 0.1f; + climb_rate = plane.calc_altitude_error_cm() * 0.1f; } else { // otherwise estimate from pilot input climb_rate = plane.g.flybywire_climb_rate * (plane.nav_pitch_cd/(plane.aparm.pitch_limit_max*100)); @@ -1451,118 +1451,6 @@ float QuadPlane::desired_auto_yaw_rate_cds(void) const return yaw_rate; } -/* - return true if the quadplane should provide stability assistance - */ -bool QuadPlane::should_assist(float aspeed, bool have_airspeed) -{ - if (!plane.arming.is_armed_and_safety_off() || (q_assist_state == Q_ASSIST_STATE_ENUM::Q_ASSIST_DISABLED) || tailsitter.is_control_surface_tailsitter()) { - // disarmed or disabled by aux switch or because a control surface tailsitter - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - if (!tailsitter.enabled() && !( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) - || is_positive(plane.get_throttle_input()) - || plane.is_flying() ) ) { - // not in a flight mode and condition where it would be safe to turn on vertial lift motors - // skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - if (q_assist_state == Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE) { - // force enabled, no need to check thresholds - in_angle_assist = false; - angle_error_start_ms = 0; - return true; - } - - if (assist_speed <= 0) { - // disabled via speed threshold - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - // assistance due to Q_ASSIST_SPEED - // if option bit is enabled only allow assist with real airspeed sensor - if ((have_airspeed && aspeed < assist_speed) && - (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.using_airspeed_sensor())) { - in_angle_assist = false; - angle_error_start_ms = 0; - return true; - } - - const uint32_t now = AP_HAL::millis(); - - /* - optional assistance when altitude is too close to the ground - */ - if (assist_alt > 0) { - float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); - if (height_above_ground < assist_alt) { - if (alt_error_start_ms == 0) { - alt_error_start_ms = now; - } - if (now - alt_error_start_ms > assist_delay*1000) { - // we've been below assistant alt for Q_ASSIST_DELAY seconds - if (!in_alt_assist) { - in_alt_assist = true; - gcs().send_text(MAV_SEVERITY_WARNING, "Alt assist %.1fm", height_above_ground); - } - return true; - } - } else { - in_alt_assist = false; - alt_error_start_ms = 0; - } - } - - if (assist_angle <= 0) { - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - /* - now check if we should provide assistance due to attitude error - */ - - const uint16_t allowed_envelope_error_cd = 500U; - if (labs(ahrs.roll_sensor) <= plane.aparm.roll_limit*100 + allowed_envelope_error_cd && - ahrs.pitch_sensor < plane.aparm.pitch_limit_max*100+allowed_envelope_error_cd && - ahrs.pitch_sensor > -(allowed_envelope_error_cd-plane.aparm.pitch_limit_min*100)) { - // we are inside allowed attitude envelope - in_angle_assist = false; - angle_error_start_ms = 0; - return false; - } - - int32_t max_angle_cd = 100U*assist_angle; - if ((labs(ahrs.roll_sensor - plane.nav_roll_cd) < max_angle_cd && - labs(ahrs.pitch_sensor - plane.nav_pitch_cd) < max_angle_cd)) { - // not beyond angle error - angle_error_start_ms = 0; - in_angle_assist = false; - return false; - } - - if (angle_error_start_ms == 0) { - angle_error_start_ms = now; - } - bool ret = (now - angle_error_start_ms) >= assist_delay*1000; - if (ret && !in_angle_assist) { - in_angle_assist = true; - gcs().send_text(MAV_SEVERITY_WARNING, "Angle assist r=%d p=%d", - (int)(ahrs.roll_sensor/100), - (int)(ahrs.pitch_sensor/100)); - } - return ret; -} - /* update for transition from quadplane to fixed wing mode */ @@ -1581,7 +1469,7 @@ void SLT_Transition::update() /* see if we should provide some assistance */ - if (quadplane.should_assist(aspeed, have_airspeed)) { + if (quadplane.assist.should_assist(aspeed, have_airspeed)) { // the quad should provide some assistance to the plane quadplane.assisted_flight = true; // update transition state for vehicles using airspeed wait @@ -1790,6 +1678,9 @@ void SLT_Transition::VTOL_update() transition_state = TRANSITION_AIRSPEED_WAIT; } last_throttle = motors->get_throttle(); + + // Keep assistance reset while not checking + quadplane.assist.reset(); } /* @@ -2468,7 +2359,7 @@ void QuadPlane::vtol_position_controller(void) } // speed for crossover to POSITION1 controller - const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist_speed); + const float aspeed_threshold = MAX(plane.aparm.airspeed_min-2, assist.speed); // run fixed wing navigation plane.nav_controller->update_waypoint(plane.auto_state.crosstrack ? plane.prev_WP_loc : plane.current_loc, loc); @@ -3721,6 +3612,32 @@ void QuadPlane::Log_Write_QControl_Tuning() target_climb_rate_cms = pos_control->get_vel_target_z_cms(); } + // Asemble assistance bitmask, defintion here is used to generate log documentation + enum class log_assistance_flags { + in_assisted_flight = 1U<<0, // true if VTOL assist is active + forced = 1U<<1, // true if assistance is forced + speed = 1U<<2, // true if assistance due to low airspeed + alt = 1U<<3, // true if assistance due to low altitude + angle = 1U<<4, // true if assistance due to attitude error + }; + + uint8_t assist_flags = 0; + if (assisted_flight) { + assist_flags |= (uint8_t)log_assistance_flags::in_assisted_flight; + } + if (assist.in_force_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::forced; + } + if (assist.in_speed_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::speed; + } + if (assist.in_alt_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::alt; + } + if (assist.in_angle_assist()) { + assist_flags |= (uint8_t)log_assistance_flags::angle; + } + struct log_QControl_Tuning pkt = { LOG_PACKET_HEADER_INIT(LOG_QTUN_MSG), time_us : AP_HAL::micros64(), @@ -3735,12 +3652,15 @@ void QuadPlane::Log_Write_QControl_Tuning() climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()), throttle_mix : attitude_control->get_throttle_mix(), transition_state : transition->get_log_transition_state(), - assist : assisted_flight, + assist : assist_flags, }; plane.logger.WriteBlock(&pkt, sizeof(pkt)); // write multicopter position control message pos_control->write_log(); + + // Write tiltrotor tilt angle log + tiltrotor.write_log(); } #endif @@ -4567,6 +4487,9 @@ void SLT_Transition::force_transition_complete() { transition_start_ms = 0; transition_low_airspeed_ms = 0; set_last_fw_pitch(); + + // Keep assistance reset while not checking + quadplane.assist.reset(); } MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 5b2b35fa92dff..2ced92498b423 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -26,6 +26,7 @@ #include "tailsitter.h" #include "tiltrotor.h" #include "transition.h" +#include "VTOL_Assist.h" /* QuadPlane specific functionality @@ -45,6 +46,7 @@ class QuadPlane friend class Tiltrotor; friend class SLT_Transition; friend class Tailsitter_Transition; + friend class VTOL_Assist; friend class Mode; friend class ModeManual; @@ -162,13 +164,6 @@ class QuadPlane MAV_TYPE get_mav_type(void) const; - enum Q_ASSIST_STATE_ENUM { - Q_ASSIST_DISABLED, - Q_ASSIST_ENABLED, - Q_ASSIST_FORCE, - }; - void set_q_assist_state(Q_ASSIST_STATE_ENUM state) {q_assist_state = state;}; - // called when we change mode (for any mode, not just Q modes) void mode_enter(void); @@ -232,9 +227,6 @@ class QuadPlane // return true if airmode should be active bool air_mode_active() const; - // check for quadplane assistance needed - bool should_assist(float aspeed, bool have_airspeed); - // check for an EKF yaw reset void check_yaw_reset(void); @@ -336,18 +328,8 @@ class QuadPlane AP_Int16 rc_speed; - // speed below which quad assistance is given - AP_Float assist_speed; - - // angular error at which quad assistance is given - AP_Int8 assist_angle; - uint32_t angle_error_start_ms; - AP_Float assist_delay; - - // altitude to trigger assistance - AP_Int16 assist_alt; - uint32_t alt_error_start_ms; - bool in_alt_assist; + // VTOL assistance in a forward flight mode + VTOL_Assist assist {*this}; // landing speed in m/s AP_Float land_final_speed; @@ -459,9 +441,6 @@ class QuadPlane // true when quad is assisting a fixed wing mode bool assisted_flight:1; - // true when in angle assist - bool in_angle_assist:1; - // are we in a guided takeoff? bool guided_takeoff:1; @@ -685,9 +664,6 @@ class QuadPlane // returns true if the vehicle should currently be doing a spiral landing bool landing_with_fixed_wing_spiral_approach(void) const; - // Q assist state, can be enabled, disabled or force. Default to enabled - Q_ASSIST_STATE_ENUM q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED; - /* return true if we should use the fixed wing attitude control loop */ diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 24c8659d0e54d..cc4d4dde104e3 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -348,43 +348,40 @@ void Plane::airbrake_update(void) } /* - setup servos for idle mode + setup servos for idle wiggle mode Idle mode is used during balloon launch to keep servos still, apart from occasional wiggle to prevent freezing up */ -void Plane::set_servos_idle(void) +void ModeAuto::wiggle_servos() { + // This is only active while in AUTO running NAV_ALTITUDE_WAIT with wiggle_time > 0 + if (wiggle.last_ms == 0) { + return; + } + int16_t servo_value; // move over full range for 2 seconds - if (auto_state.idle_wiggle_stage != 0) { - auto_state.idle_wiggle_stage += 2; + if (wiggle.stage != 0) { + wiggle.stage += 2; } - if (auto_state.idle_wiggle_stage == 0) { + if (wiggle.stage == 0) { servo_value = 0; - } else if (auto_state.idle_wiggle_stage < 50) { - servo_value = auto_state.idle_wiggle_stage * (4500 / 50); - } else if (auto_state.idle_wiggle_stage < 100) { - servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50); - } else if (auto_state.idle_wiggle_stage < 150) { - servo_value = (100 - auto_state.idle_wiggle_stage) * (4500 / 50); - } else if (auto_state.idle_wiggle_stage < 200) { - servo_value = (auto_state.idle_wiggle_stage-200) * (4500 / 50); + } else if (wiggle.stage < 50) { + servo_value = wiggle.stage * (4500 / 50); + } else if (wiggle.stage < 100) { + servo_value = (100 - wiggle.stage) * (4500 / 50); + } else if (wiggle.stage < 150) { + servo_value = (100 - wiggle.stage) * (4500 / 50); + } else if (wiggle.stage < 200) { + servo_value = (wiggle.stage-200) * (4500 / 50); } else { - auto_state.idle_wiggle_stage = 0; + wiggle.stage = 0; servo_value = 0; } SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_value); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_value); SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); - - SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); - SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft); - SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight); - } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 0191184d505b6..21785ccff1ec2 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -2,13 +2,6 @@ #include "qautotune.h" -/***************************************************************************** -* The init_ardupilot function processes everything we need for an in - air restart -* We will determine later if we are actually on the ground and process a -* ground start in that case. -* -*****************************************************************************/ - static void failsafe_check_static() { plane.failsafe_check(); @@ -109,40 +102,7 @@ void Plane::init_ardupilot() #endif AP_Param::reload_defaults_file(true); - - startup_ground(); - - // don't initialise aux rc output until after quadplane is setup as - // that can change initial values of channels - init_rc_out_aux(); - - if (g2.oneshot_mask != 0) { - hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); - } - - set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED); - - // set the correct flight mode - // --------------------------- - rc().reset_mode_switch(); - - // initialise sensor -#if AP_OPTICALFLOW_ENABLED - if (optflow.enabled()) { - optflow.init(-1); - } -#endif - -#if AC_PRECLAND_ENABLED - g2.precland.init(scheduler.get_loop_rate_hz()); -#endif -} -//******************************************************************************** -//This function does all the calibrations, etc. that we need during a ground start -//******************************************************************************** -void Plane::startup_ground(void) -{ set_mode(mode_initializing, ModeReason::INITIALISED); #if (GROUND_START_DELAY > 0) @@ -155,7 +115,7 @@ void Plane::startup_ground(void) //INS ground start //------------------------ // - startup_INS_ground(); + startup_INS(); // Save the settings for in-air restart // ------------------------------------ @@ -174,8 +134,32 @@ void Plane::startup_ground(void) // reset last heartbeat time, so we don't trigger failsafe on slow // startup gcs().sysid_myggcs_seen(AP_HAL::millis()); -} + // don't initialise aux rc output until after quadplane is setup as + // that can change initial values of channels + init_rc_out_aux(); + + if (g2.oneshot_mask != 0) { + hal.rcout->set_output_mode(g2.oneshot_mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT); + } + + set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED); + + // set the correct flight mode + // --------------------------- + rc().reset_mode_switch(); + + // initialise sensor +#if AP_OPTICALFLOW_ENABLED + if (optflow.enabled()) { + optflow.init(-1); + } +#endif + +#if AC_PRECLAND_ENABLED + g2.precland.init(scheduler.get_loop_rate_hz()); +#endif +} #if AP_FENCE_ENABLED /* @@ -418,7 +402,7 @@ void Plane::check_short_failsafe() } -void Plane::startup_INS_ground(void) +void Plane::startup_INS(void) { if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) { gcs().send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration. Do not move plane"); diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 4e28d534440a3..bac8e4d9f7de3 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -233,7 +233,7 @@ void Tailsitter::setup() // Setup for control surface less operation if (enable == 2) { - quadplane.q_assist_state = QuadPlane::Q_ASSIST_STATE_ENUM::Q_ASSIST_FORCE; + quadplane.assist.set_state(VTOL_Assist::STATE::FORCE_ENABLED); quadplane.air_mode = AirMode::ASSISTED_FLIGHT_ONLY; // Do not allow arming in forward flight modes @@ -707,7 +707,7 @@ void Tailsitter::speed_scaling(void) // (mass / A) is disk loading DL so: // Ue^2 = (((t / t_h) * DL * 9.81)/(0.5 * rho)) + U0^2 - const float rho = SSL_AIR_DENSITY * plane.barometer.get_air_density_ratio(); + const float rho = SSL_AIR_DENSITY * quadplane.ahrs.get_air_density_ratio(); float hover_rho = rho; if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { // if applying altitude correction use sea level density for hover case @@ -752,7 +752,7 @@ void Tailsitter::speed_scaling(void) if ((gain_scaling_mask & TAILSITTER_GSCL_ALTITUDE) != 0) { // air density correction - spd_scaler /= plane.barometer.get_air_density_ratio(); + spd_scaler /= quadplane.ahrs.get_air_density_ratio(); } const SRV_Channel::Aux_servo_function_t functions[] = { @@ -819,7 +819,7 @@ void Tailsitter_Transition::update() float aspeed; bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); - quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed); + quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed); if (transition_state < TRANSITION_DONE) { // during transition we ask TECS to use a synthetic @@ -885,7 +885,7 @@ void Tailsitter_Transition::VTOL_update() float aspeed; bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed); // provide assistance in forward flight portion of tailsitter transition - quadplane.assisted_flight = quadplane.should_assist(aspeed, have_airspeed); + quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed); if (!quadplane.tailsitter.transition_vtol_complete()) { return; } @@ -894,6 +894,9 @@ void Tailsitter_Transition::VTOL_update() vtol_limit_start_ms = now; vtol_limit_initial_pitch = quadplane.ahrs_view->pitch_sensor; } + } else { + // Keep assistance reset while not checking + quadplane.assist.reset(); } restart(); } @@ -1006,6 +1009,8 @@ void Tailsitter_Transition::force_transition_complete() vtol_transition_start_ms = AP_HAL::millis(); vtol_transition_initial_pitch = constrain_float(plane.nav_pitch_cd,-8500,8500); fw_limit_start_ms = 0; + + quadplane.assist.reset(); } MAV_VTOL_STATE Tailsitter_Transition::get_mav_vtol_state() const diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 0be2a07845282..7a8de87a72ed1 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; @@ -394,6 +394,33 @@ void Tiltrotor::update(void) } } +#if HAL_LOGGING_ENABLED +// Write tiltrotor specific log +void Tiltrotor::write_log() +{ + struct log_tiltrotor pkt { + LOG_PACKET_HEADER_INIT(LOG_TILT_MSG), + time_us : AP_HAL::micros64(), + current_tilt : current_tilt * 90.0, + }; + + if (type != TILT_TYPE_VECTORED_YAW) { + // Left and right tilt are invalid + pkt.front_left_tilt = plane.logger.quiet_nanf(); + pkt.front_right_tilt = plane.logger.quiet_nanf(); + + } else { + // Calculate tilt angle from servo outputs + const float total_angle = 90.0 + tilt_yaw_angle + fixed_angle; + const float scale = total_angle * 0.001; + pkt.front_left_tilt = (SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorLeft) * scale) - tilt_yaw_angle; + pkt.front_right_tilt = (SRV_Channels::get_output_scaled(SRV_Channel::k_tiltMotorRight) * scale) - tilt_yaw_angle; + } + + plane.logger.WriteBlock(&pkt, sizeof(pkt)); +} +#endif + /* tilt compensation for angle of tilt. When the rotors are tilted the roll effect of differential thrust on the tilted rotors is decreased diff --git a/ArduPlane/tiltrotor.h b/ArduPlane/tiltrotor.h index 95ddd84181b81..3add549b7113d 100644 --- a/ArduPlane/tiltrotor.h +++ b/ArduPlane/tiltrotor.h @@ -16,6 +16,7 @@ #include #include "transition.h" +#include class QuadPlane; class AP_MotorsMulticopter; @@ -69,6 +70,9 @@ friend class Tiltrotor_Transition; // always return true if not enabled or not a continuous type bool tilt_angle_achieved() const { return !enabled() || (type != TILT_TYPE_CONTINUOUS) || angle_achieved; } + // Write tiltrotor specific log + void write_log(); + AP_Int8 enable; AP_Int16 tilt_mask; AP_Int16 max_rate_up_dps; @@ -98,6 +102,15 @@ friend class Tiltrotor_Transition; private: + // Tiltrotor specific log message + struct PACKED log_tiltrotor { + LOG_PACKET_HEADER; + uint64_t time_us; + float current_tilt; + float front_left_tilt; + float front_right_tilt; + }; + bool setup_complete; // true if a fixed forward motor is setup diff --git a/ArduPlane/wscript b/ArduPlane/wscript index d983bb59bacee..78fad7650e377 100644 --- a/ArduPlane/wscript +++ b/ArduPlane/wscript @@ -10,18 +10,15 @@ def build(bld): 'APM_Control', 'AP_AdvancedFailsafe', 'AP_Avoidance', - 'AP_Arming', 'AP_Camera', 'AP_L1_Control', 'AP_Navigation', - 'AP_RCMapper', 'AP_TECS', 'AP_InertialNav', 'AC_WPNav', 'AC_AttitudeControl', 'AP_Motors', 'AP_Landing', - 'AP_Beacon', 'PID', 'AP_Soaring', 'AP_LTM_Telem', diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 507a22fb1b814..c3ba73b8912a8 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -79,7 +79,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(update_altitude, 10, 100, 18), SCHED_TASK(three_hz_loop, 3, 75, 21), SCHED_TASK(update_turn_counter, 10, 50, 24), - SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90, 27), SCHED_TASK(one_hz_loop, 1, 100, 33), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39), diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 5795c5016843d..6854c9332852f 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -382,9 +382,11 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "RC3_TRIM", 1100}, { "COMPASS_OFFS_MAX", 1000}, { "INS_GYR_CAL", 0}, +#if HAL_MOUNT_ENABLED { "MNT1_TYPE", 1}, { "MNT1_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING}, { "MNT1_RC_RATE", 30}, +#endif { "RC7_OPTION", 214}, // MOUNT1_YAW { "RC8_OPTION", 213}, // MOUNT1_PITCH { "MOT_PWM_MIN", 1100}, @@ -395,7 +397,9 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "PSC_VELXY_P", 6.0f}, { "EK3_SRC1_VELZ", 0}, #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR +#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED { "BARO_PROBE_EXT", 0}, +#endif { "BATT_MONITOR", 4}, { "BATT_CAPACITY", 0}, { "LEAK1_PIN", 27}, @@ -405,7 +409,9 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "SERVO16_FUNCTION", 7}, // k_mount_tilt { "SERVO16_REVERSED", 1}, #else +#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED { "BARO_PROBE_EXT", 768}, +#endif { "SERVO9_FUNCTION", 59}, // k_rcin9, lights 1 { "SERVO10_FUNCTION", 7}, // k_mount_tilt #endif diff --git a/ArduSub/mode.cpp b/ArduSub/mode.cpp index 29d314d72af47..d445dd5c8c16d 100644 --- a/ArduSub/mode.cpp +++ b/ArduSub/mode.cpp @@ -249,7 +249,7 @@ void Mode::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int1 } // convert earth-frame level rates to body-frame level rates - attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level); + attitude_control->euler_rate_to_ang_vel(attitude_control->get_attitude_target_quat(), rate_ef_level, rate_bf_level); // combine earth frame rate corrections with rate requests if (g.acro_trainer == ACRO_TRAINER_LIMITED) { diff --git a/ArduSub/wscript b/ArduSub/wscript index 11361fbadce0d..ab0b8ce25da6d 100644 --- a/ArduSub/wscript +++ b/ArduSub/wscript @@ -14,10 +14,7 @@ def build(bld): 'AP_JSButton', 'AP_LeakDetector', 'AP_Motors', - 'AP_RCMapper', - 'AP_Beacon', 'AP_TemperatureSensor', - 'AP_Arming', ], ) diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index b4e50b2e6e0bf..1273636c2662c 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -75,7 +75,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { #if AP_SERVORELAYEVENTS_ENABLED SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27), #endif - SCHED_TASK_CLASS(AP_Baro, &blimp.barometer, accumulate, 50, 90, 30), #if HAL_LOGGING_ENABLED SCHED_TASK(full_rate_logging, 50, 50, 33), #endif diff --git a/Blimp/wscript b/Blimp/wscript index 664dd1aeb4dbd..2314b7504443f 100644 --- a/Blimp/wscript +++ b/Blimp/wscript @@ -9,13 +9,10 @@ def build(bld): ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AC_InputManager', 'AP_InertialNav', - 'AP_RCMapper', 'AP_Avoidance', - 'AP_Arming', 'AP_LTM_Telem', 'AP_Devo_Telem', 'AP_KDECAN', - 'AP_Beacon', 'AP_AdvancedFailsafe', # TODO for some reason compiling GCS_Common.cpp (in libraries) fails if this isn't included. 'AC_AttitudeControl', # for PSCx logging ], diff --git a/README.md b/README.md index e015b750ff32b..2121f8f21fdf6 100644 --- a/README.md +++ b/README.md @@ -96,8 +96,6 @@ for reviewing patches on their specific area. - ***Vehicle***: Rover - [Willian Galvani](https://github.com/williangalvani): - ***Vehicle***: Sub -- [Lucas De Marchi](https://github.com/lucasdemarchi): - - ***Subsystem***: Linux - [Michael du Breuil](https://github.com/WickedShell): - ***Subsystem***: Batteries - ***Subsystem***: GPS diff --git a/Rover/AP_ExternalControl_Rover.cpp b/Rover/AP_ExternalControl_Rover.cpp index 1c08f92a9b5fd..d7511f6f0f832 100644 --- a/Rover/AP_ExternalControl_Rover.cpp +++ b/Rover/AP_ExternalControl_Rover.cpp @@ -29,6 +29,12 @@ bool AP_ExternalControl_Rover::set_linear_velocity_and_yaw_rate(const Vector3f & return true; } +bool AP_ExternalControl_Rover::set_global_position(const Location& loc) +{ + // set_target_location only checks if the rover is in guided mode or not + return rover.set_target_location(loc); +} + bool AP_ExternalControl_Rover::ready_for_external_control() { return rover.control_mode->in_guided_mode() && rover.arming.is_armed(); diff --git a/Rover/AP_ExternalControl_Rover.h b/Rover/AP_ExternalControl_Rover.h index 434972833e45d..e7350ebbe2c62 100644 --- a/Rover/AP_ExternalControl_Rover.h +++ b/Rover/AP_ExternalControl_Rover.h @@ -7,7 +7,8 @@ #if AP_EXTERNAL_CONTROL_ENABLED -class AP_ExternalControl_Rover : public AP_ExternalControl { +class AP_ExternalControl_Rover : public AP_ExternalControl +{ public: /* Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. @@ -15,6 +16,12 @@ class AP_ExternalControl_Rover : public AP_ExternalControl { Yaw is in earth frame, NED [rad/s]. */ bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)override WARN_IF_UNUSED; + + /* + Sets the global position for loiter point + */ + bool set_global_position(const Location& loc) override WARN_IF_UNUSED; + private: /* Return true if Rover is ready to handle external control data. diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index f38e8f3dd0498..6189b2d281ef9 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -124,11 +124,11 @@ void GCS_MAVLINK_Rover::send_servo_out() { float motor1, motor3; if (rover.g2.motors.have_skid_steering()) { - motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) / 1000.0f); - motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) / 1000.0f); + motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) * 0.001f); + motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) * 0.001f); } else { motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_steering) / 4500.0f); - motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 100.0f); + motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f); } mavlink_msg_rc_channels_scaled_send( chan, diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 9d0e0b5a84e9d..83e7966e79406 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -110,7 +110,7 @@ const AP_Param::Info Rover::var_info[] = { // @Param: FS_ACTION // @DisplayName: Failsafe Action // @Description: What to do on a failsafe event - // @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold + // @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold,5:Terminate // @User: Standard GSCALAR(fs_action, "FS_ACTION", (int8_t)FailsafeAction::Hold), @@ -642,9 +642,9 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_GROUPINFO("FS_OPTIONS", 48, ParametersG2, fs_options, 0), #if HAL_TORQEEDO_ENABLED - // @Group: TRQD_ + // @Group: TRQ // @Path: ../libraries/AP_Torqeedo/AP_Torqeedo.cpp - AP_SUBGROUPINFO(torqeedo, "TRQD_", 49, ParametersG2, AP_Torqeedo), + AP_SUBGROUPINFO(torqeedo, "TRQ", 49, ParametersG2, AP_Torqeedo), #endif // @Group: PSC @@ -808,6 +808,13 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_g2, 722, AP_PARAM_INT8, "PRX1_IGN_WID4" }, { Parameters::k_param_g2, 1234, AP_PARAM_FLOAT, "PRX1_MIN" }, { Parameters::k_param_g2, 1298, AP_PARAM_FLOAT, "PRX1_MAX" }, + { Parameters::k_param_g2, 113, AP_PARAM_INT8, "TRQ1_TYPE" }, + { Parameters::k_param_g2, 177, AP_PARAM_INT8, "TRQ1_ONOFF_PIN" }, + { Parameters::k_param_g2, 241, AP_PARAM_INT8, "TRQ1_DE_PIN" }, + { Parameters::k_param_g2, 305, AP_PARAM_INT16, "TRQ1_OPTIONS" }, + { Parameters::k_param_g2, 369, AP_PARAM_INT8, "TRQ1_POWER" }, + { Parameters::k_param_g2, 433, AP_PARAM_FLOAT, "TRQ1_SLEW_TIME" }, + { Parameters::k_param_g2, 497, AP_PARAM_FLOAT, "TRQ1_DIR_DELAY" }, }; diff --git a/Rover/ReleaseNotes.txt b/Rover/ReleaseNotes.txt index 940bcb44de0d1..29e03c68cedf3 100644 --- a/Rover/ReleaseNotes.txt +++ b/Rover/ReleaseNotes.txt @@ -1,5 +1,71 @@ Rover Release Notes: -------------------- + +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/Rover.cpp b/Rover/Rover.cpp index f1a47b452545d..3bf4c1f274b6d 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -157,8 +157,8 @@ Rover::Rover(void) : { } -#if AP_SCRIPTING_ENABLED -// set target location (for use by scripting) +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +// set target location (for use by external control and scripting) bool Rover::set_target_location(const Location& target_loc) { // exit if vehicle is not in Guided mode or Auto-Guided mode @@ -168,7 +168,9 @@ bool Rover::set_target_location(const Location& target_loc) return mode_guided.set_desired_location(target_loc); } +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED // set target velocity (for use by scripting) bool Rover::set_target_velocity_NED(const Vector3f& vel_ned) { @@ -244,19 +246,19 @@ bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float & control_value = constrain_float(g2.motors.get_walking_height(), -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::Throttle: - control_value = constrain_float(g2.motors.get_throttle() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_throttle() * 0.01f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::Yaw: control_value = constrain_float(g2.motors.get_steering() / 4500.0f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::Lateral: - control_value = constrain_float(g2.motors.get_lateral() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_lateral() * 0.01f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::MainSail: - control_value = constrain_float(g2.motors.get_mainsail() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_mainsail() * 0.01f, -1.0f, 1.0f); return true; case AP_Vehicle::ControlOutput::WingSail: - control_value = constrain_float(g2.motors.get_wingsail() / 100.0f, -1.0f, 1.0f); + control_value = constrain_float(g2.motors.get_wingsail() * 0.01f, -1.0f, 1.0f); return true; default: return false; diff --git a/Rover/Rover.h b/Rover/Rover.h index 8873b844e2946..0db95d23b3997 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -269,8 +269,11 @@ class Rover : public AP_Vehicle { cruise_learn_t cruise_learn; // Rover.cpp -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED bool set_target_location(const Location& target_loc) override; +#endif + +#if AP_SCRIPTING_ENABLED bool set_target_velocity_NED(const Vector3f& vel_ned) override; bool set_steering_and_throttle(float steering, float throttle) override; bool get_steering_and_throttle(float& steering, float& throttle) override; @@ -393,7 +396,7 @@ class Rover : public AP_Vehicle { return control_mode == &mode_auto; } - void startup_INS_ground(void); + void startup_INS(void); void notify_mode(const Mode *new_mode); uint8_t check_digital_pin(uint8_t pin); bool should_log(uint32_t mask); diff --git a/Rover/Steering.cpp b/Rover/Steering.cpp index 5253c2dfbebb6..5724c46976b9c 100644 --- a/Rover/Steering.cpp +++ b/Rover/Steering.cpp @@ -10,10 +10,8 @@ void Rover::set_servos(void) motor_test_output(); } else { // get ground speed - float speed; - if (!g2.attitude_control.get_forward_speed(speed)) { - speed = 0.0f; - } + float speed = 0.0f; + g2.attitude_control.get_forward_speed(speed); g2.motors.output(arming.is_armed(), speed, G_Dt); } diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 20d06a1d7d7b8..f4bd7dfc30929 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -111,7 +111,7 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t // we proportionally reduce steering and throttle if (g2.motors.have_skid_steering()) { const float steer_normalised = constrain_float(steering_out / 4500.0f, -1.0f, 1.0f); - const float throttle_normalised = constrain_float(throttle_out / 100.0f, -1.0f, 1.0f); + const float throttle_normalised = constrain_float(throttle_out * 0.01f, -1.0f, 1.0f); const float saturation_value = fabsf(steer_normalised) + fabsf(throttle_normalised); if (saturation_value > 1.0f) { steering_out /= saturation_value; diff --git a/Rover/mode_guided.cpp b/Rover/mode_guided.cpp index 96ab7e15651d4..80f0a5fa4477b 100644 --- a/Rover/mode_guided.cpp +++ b/Rover/mode_guided.cpp @@ -82,7 +82,7 @@ void ModeGuided::update() } if (have_attitude_target) { // run steering and throttle controllers - float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds / 100.0f), + float steering_out = attitude_control.get_steering_out_rate(radians(_desired_yaw_rate_cds * 0.01f), g2.motors.limit.steer_left, g2.motors.limit.steer_right, rover.G_Dt); 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/sailboat.cpp b/Rover/sailboat.cpp index 7fb957e06c628..24b11dea09178 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -275,9 +275,9 @@ void Sailboat::relax_sails() // calculate throttle and mainsail angle required to attain desired speed (in m/s) void Sailboat::get_throttle_and_set_mainsail(float desired_speed, float &throttle_out) { + throttle_out = 0.0f; if (!sail_enabled()) { relax_sails(); - throttle_out = 0.0f; return; } @@ -292,8 +292,6 @@ void Sailboat::get_throttle_and_set_mainsail(float desired_speed, float &throttl rover.g.speed_cruise, rover.g.throttle_cruise * 0.01f, rover.G_Dt); - } else { - throttle_out = 0.0f; } if (motor_state == UseMotor::USE_MOTOR_ALWAYS) { diff --git a/Rover/system.cpp b/Rover/system.cpp index e0c4c9ce5b4d2..b00c2cae1e405 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -1,10 +1,3 @@ -/***************************************************************************** -The init_ardupilot function processes everything we need for an in - air restart - We will determine later if we are actually on the ground and process a - ground start in that case. - -*****************************************************************************/ - #include "Rover.h" static void failsafe_check_static() @@ -121,7 +114,21 @@ void Rover::init_ardupilot() g2.oa.init(); #endif - startup_ground(); + set_mode(mode_initializing, ModeReason::INITIALISED); + + startup_INS(); + +#if AP_MISSION_ENABLED + // initialise mission library + mode_auto.mission.init(); +#endif + + // initialise AP_Logger library +#if HAL_LOGGING_ENABLED + logger.setVehicle_Startup_Writer( + FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) + ); +#endif Mode *initial_mode = mode_from_mode_num((enum Mode::Number)g.initial_mode.get()); if (initial_mode == nullptr) { @@ -145,30 +152,6 @@ void Rover::init_ardupilot() initialised = true; } -//********************************************************************************* -// This function does all the calibrations, etc. that we need during a ground start -//********************************************************************************* -void Rover::startup_ground(void) -{ - set_mode(mode_initializing, ModeReason::INITIALISED); - - // IMU ground start - //------------------------ - // - - startup_INS_ground(); - - // initialise mission library - mode_auto.mission.init(); - - // initialise AP_Logger library -#if HAL_LOGGING_ENABLED - logger.setVehicle_Startup_Writer( - FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) - ); -#endif -} - // update the ahrs flyforward setting which can allow // the vehicle's movements to be used to estimate heading void Rover::update_ahrs_flyforward() @@ -285,7 +268,7 @@ bool Rover::set_mode(Mode::Number new_mode, ModeReason reason) return rover.set_mode(*mode, reason); } -void Rover::startup_INS_ground(void) +void Rover::startup_INS(void) { gcs().send_text(MAV_SEVERITY_INFO, "Beginning INS calibration. Do not move vehicle"); hal.scheduler->delay(100); diff --git a/Rover/wscript b/Rover/wscript index f3fe0a0df63bd..2df7db6be56fb 100644 --- a/Rover/wscript +++ b/Rover/wscript @@ -8,12 +8,9 @@ def build(bld): ap_vehicle=vehicle, ap_libraries=bld.ap_common_vehicle_libraries() + [ 'APM_Control', - 'AP_Arming', 'AP_Mount', 'AP_Navigation', 'AR_WPNav', - 'AP_RCMapper', - 'AP_Beacon', 'AP_AdvancedFailsafe', 'AP_WheelEncoder', 'AP_SmartRTL', diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index c353daa5a8711..1348e0926ebf7 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -273,6 +273,12 @@ 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 @@ -291,6 +297,12 @@ 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 @@ -319,6 +331,9 @@ 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 @@ -326,3 +341,6 @@ AP_HW_Holybro-PERIPH-H7 5404 # 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/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index f02037e5a2dc2..be0d8c32d4458 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -208,7 +208,7 @@ void AP_Periph_FW::init() #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) && (HAL_USE_I2C == TRUE) const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01); if (pins_enabled) { ChibiOS::I2CBus::set_bus_to_floating(0); @@ -227,15 +227,20 @@ void AP_Periph_FW::init() #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - if (rangefinder.get_type(0) != RangeFinder::Type::NONE) { - if (g.rangefinder_port >= 0) { + bool have_rangefinder = false; + for (uint8_t i=0; i= 0)) { // init uart for serial rangefinders - auto *uart = hal.serial(g.rangefinder_port); + auto *uart = hal.serial(g.rangefinder_port[i]); if (uart != nullptr) { - uart->begin(g.rangefinder_baud); - serial_manager.set_protocol_and_baud(g.rangefinder_port, AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud); + uart->begin(g.rangefinder_baud[i]); + serial_manager.set_protocol_and_baud(g.rangefinder_port[i], AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud[i]); + have_rangefinder = true; } } + } + if (have_rangefinder) { + // Can only call rangefinder init once, subsequent inits are blocked rangefinder.init(ROTATION_NONE); } #endif @@ -419,7 +424,14 @@ void AP_Periph_FW::update() hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature()); #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - hal.serial(0)->printf("RNG %u %ucm\n", rangefinder.num_sensors(), rangefinder.distance_cm_orient(ROTATION_NONE)); + hal.serial(0)->printf("Num RNG sens %u\n", rangefinder.num_sensors()); + for (uint8_t i=0; iprintf("RNG %u %ucm\n", i, uint16_t(backend->distance()*100)); + } #endif hal.scheduler->delay(1); #endif diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 95d32af7936ff..b6db8f6a11c2c 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -12,6 +12,7 @@ #include #include #include +#include #include #include #include @@ -90,6 +91,10 @@ #endif #endif +#if defined(HAL_PERIPH_ENABLE_RPM_STREAM) && !defined(HAL_PERIPH_ENABLE_RPM) + #error "HAL_PERIPH_ENABLE_RPM_STREAM requires HAL_PERIPH_ENABLE_RPM" +#endif + #ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED #define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT) #endif @@ -168,7 +173,9 @@ class AP_Periph_FW { void send_relposheading_msg(); void can_baro_update(); void can_airspeed_update(); +#ifdef HAL_PERIPH_ENABLE_RANGEFINDER void can_rangefinder_update(); +#endif void can_battery_update(); void can_battery_send_cells(uint8_t instance); void can_proximity_update(); @@ -226,7 +233,12 @@ class AP_Periph_FW { #ifdef HAL_PERIPH_ENABLE_RPM AP_RPM rpm_sensor; uint32_t rpm_last_update_ms; +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + void rpm_sensor_send(); + uint32_t rpm_last_send_ms; + uint8_t rpm_last_sent_index; #endif +#endif // HAL_PERIPH_ENABLE_RPM #ifdef HAL_PERIPH_ENABLE_BATTERY void handle_battery_failsafe(const char* type_str, const int8_t action) { } @@ -279,7 +291,8 @@ class AP_Periph_FW { #ifdef HAL_PERIPH_ENABLE_RANGEFINDER RangeFinder rangefinder; - uint32_t last_sample_ms; + uint32_t last_rangefinder_update_ms; + uint32_t last_rangefinder_sample_ms[RANGEFINDER_MAX_INSTANCES]; #endif #ifdef HAL_PERIPH_ENABLE_PROXIMITY @@ -451,7 +464,16 @@ class AP_Periph_FW { bool debug_option_is_set(const DebugOptions option) const { return (uint8_t(g.debug.get()) & (1U< 1 + // @Param: RNGFND2_BAUDRATE + // @DisplayName: Rangefinder serial baudrate + // @Description: Rangefinder serial baudrate. + // @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000 + // @Increment: 1 + // @User: Standard + // @RebootRequired: True + GARRAY(rangefinder_baud, 1, "RNGFND2_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT), + + // @Param: RNGFND2_PORT + // @DisplayName: Rangefinder Serial Port + // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder. + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced + // @RebootRequired: True + GARRAY(rangefinder_port, 1, "RNGFND2_PORT", -1), +#endif // @Param: RNGFND_MAX_RATE // @DisplayName: Rangefinder max rate @@ -661,6 +685,24 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GSCALAR(temperature_msg_rate, "TEMP_MSG_RATE", 0), #endif + // @Param: OPTIONS + // @DisplayName: AP Periph Options + // @Description: Bitmask of AP Periph Options + // @Bitmask: 0: Enable continuous sensor probe + // @User: Standard + GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS), + +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + // @Param: RPM_MSG_RATE + // @DisplayName: RPM sensor message rate + // @Description: This is the rate RPM sensor data is sent in Hz. Zero means no send. Each sensor with a set ID is sent in turn. + // @Units: Hz + // @Range: 0 200 + // @Increment: 1 + // @User: Standard + GSCALAR(rpm_msg_rate, "RPM_MSG_RATE", 0), +#endif + AP_VAREND }; diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 94ac49b39ac05..d68e38f7b4ecc 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -25,7 +25,7 @@ class Parameters { k_param_airspeed, k_param_rangefinder, k_param_flash_bootloader, - k_param_rangefinder_baud, + k_param_rangefinder_baud0, k_param_adsb_baudrate, k_param_hardpoint_id, k_param_hardpoint_rate, @@ -36,7 +36,7 @@ class Parameters { k_param_serial_number, k_param_adsb_port, k_param_servo_channels, - k_param_rangefinder_port, + k_param_rangefinder_port0, k_param_gps_port, k_param_msp_port, k_param_notify, @@ -91,6 +91,10 @@ class Parameters { k_param_serial_options, k_param_relay, k_param_temperature_msg_rate, + k_param_rangefinder_baud1, + k_param_rangefinder_port1, + k_param_options, + k_param_rpm_msg_rate, }; AP_Int16 format_version; @@ -119,8 +123,8 @@ class Parameters { #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - AP_Int32 rangefinder_baud; - AP_Int8 rangefinder_port; + AP_Int32 rangefinder_baud[RANGEFINDER_MAX_INSTANCES]; + AP_Int8 rangefinder_port[RANGEFINDER_MAX_INSTANCES]; AP_Int16 rangefinder_max_rate; #endif @@ -209,6 +213,10 @@ class Parameters { AP_Int8 temperature_msg_rate; #endif +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + AP_Int16 rpm_msg_rate; +#endif + #if HAL_CANFD_SUPPORTED AP_Int8 can_fdmode; AP_Int8 can_fdbaudrate[HAL_NUM_CAN_IFACES]; @@ -216,6 +224,8 @@ class Parameters { static constexpr uint8_t can_fdmode = 0; #endif + AP_Int32 options; + AP_Int8 can_terminate[HAL_NUM_CAN_IFACES]; AP_Int8 node_stats; diff --git a/Tools/AP_Periph/airspeed.cpp b/Tools/AP_Periph/airspeed.cpp index 17a4da160731c..579b1f04bc5a0 100644 --- a/Tools/AP_Periph/airspeed.cpp +++ b/Tools/AP_Periph/airspeed.cpp @@ -21,7 +21,7 @@ void AP_Periph_FW::can_airspeed_update(void) return; } #if AP_PERIPH_PROBE_CONTINUOUS - if (!airspeed.healthy()) { + if (option_is_set(PeriphOptions::PROBE_CONTINUOUS) && !hal.util->get_soft_armed() && !airspeed.healthy()) { uint32_t now = AP_HAL::millis(); static uint32_t last_probe_ms; if (now - last_probe_ms >= 1000) { diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 80ae6fbc4fc9c..1b5607cdab160 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1848,6 +1848,9 @@ void AP_Periph_FW::can_update() #endif #ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE temperature_sensor_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + rpm_sensor_send(); #endif } const uint32_t now_us = AP_HAL::micros(); diff --git a/Tools/AP_Periph/compass.cpp b/Tools/AP_Periph/compass.cpp index da5d230776115..2c70ae1cc04ff 100644 --- a/Tools/AP_Periph/compass.cpp +++ b/Tools/AP_Periph/compass.cpp @@ -40,7 +40,7 @@ void AP_Periph_FW::can_mag_update(void) compass.read(); #if AP_PERIPH_PROBE_CONTINUOUS - if (compass.get_count() == 0) { + if (option_is_set(PeriphOptions::PROBE_CONTINUOUS) && !hal.util->get_soft_armed() && (compass.get_count() == 0)) { static uint32_t last_probe_ms; uint32_t now = AP_HAL::millis(); if (now - last_probe_ms >= 1000) { diff --git a/Tools/AP_Periph/gps.cpp b/Tools/AP_Periph/gps.cpp index f185f709a0720..87b1976eb9c50 100644 --- a/Tools/AP_Periph/gps.cpp +++ b/Tools/AP_Periph/gps.cpp @@ -295,8 +295,8 @@ void AP_Periph_FW::send_relposheading_msg() { float relative_down_pos; float reported_heading_acc; uint32_t curr_timestamp = 0; - gps.get_RelPosHeading(curr_timestamp, reported_heading, relative_distance, relative_down_pos, reported_heading_acc); - if (last_relposheading_ms == curr_timestamp) { + if (!gps.get_RelPosHeading(curr_timestamp, reported_heading, relative_distance, relative_down_pos, reported_heading_acc) || + last_relposheading_ms == curr_timestamp) { return; } last_relposheading_ms = curr_timestamp; diff --git a/Tools/AP_Periph/rangefinder.cpp b/Tools/AP_Periph/rangefinder.cpp index 43ad6d65e506a..981f4dca47c49 100644 --- a/Tools/AP_Periph/rangefinder.cpp +++ b/Tools/AP_Periph/rangefinder.cpp @@ -12,6 +12,8 @@ #define AP_PERIPH_PROBE_CONTINUOUS 0 #endif +extern const AP_HAL::HAL &hal; + /* update CAN rangefinder */ @@ -21,7 +23,8 @@ void AP_Periph_FW::can_rangefinder_update(void) return; } #if AP_PERIPH_PROBE_CONTINUOUS - if (rangefinder.num_sensors() == 0) { + // We only allow continuous probing for rangefinders while vehicle is disarmed. Probing is currently inefficient and leads to longer loop times. + if ((rangefinder.num_sensors() == 0) && !hal.util->get_soft_armed() && option_is_set(PeriphOptions::PROBE_CONTINUOUS)) { uint32_t now = AP_HAL::millis(); static uint32_t last_probe_ms; if (now - last_probe_ms >= 1000) { @@ -31,67 +34,88 @@ void AP_Periph_FW::can_rangefinder_update(void) } #endif uint32_t now = AP_HAL::millis(); - static uint32_t last_update_ms; if (g.rangefinder_max_rate > 0 && - now - last_update_ms < uint32_t(1000/g.rangefinder_max_rate)) { + now - last_rangefinder_update_ms < uint32_t(1000/g.rangefinder_max_rate)) { // limit to max rate return; } - last_update_ms = now; + last_rangefinder_update_ms = now; + + // update all rangefinder instances rangefinder.update(); - RangeFinder::Status status = rangefinder.status_orient(ROTATION_NONE); - if (status <= RangeFinder::Status::NoData) { - // don't send any data - return; - } - const uint32_t sample_ms = rangefinder.last_reading_ms(ROTATION_NONE); - if (last_sample_ms == sample_ms) { - return; - } - last_sample_ms = sample_ms; - - uint16_t dist_cm = rangefinder.distance_cm_orient(ROTATION_NONE); - uavcan_equipment_range_sensor_Measurement pkt {}; - pkt.sensor_id = rangefinder.get_address(0); - switch (status) { - case RangeFinder::Status::OutOfRangeLow: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE; - break; - case RangeFinder::Status::OutOfRangeHigh: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; - break; - case RangeFinder::Status::Good: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; - break; - default: - pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_UNDEFINED; - break; - } - switch (rangefinder.get_mav_distance_sensor_type_orient(ROTATION_NONE)) { - case MAV_DISTANCE_SENSOR_LASER: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR; - break; - case MAV_DISTANCE_SENSOR_ULTRASOUND: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR; - break; - case MAV_DISTANCE_SENSOR_RADAR: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR; - break; - default: - pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_UNDEFINED; - break; - } - pkt.range = dist_cm * 0.01; + // cycle through each rangefinder instance to find one to send + // equipment.range_sensor only uses 3 CAN frames so we just send all available sensor measurements. + for (uint8_t i = 0; i <= rangefinder.num_sensors(); i++) { + + if (rangefinder.get_type(i) == RangeFinder::Type::NONE) { + continue; + } + + AP_RangeFinder_Backend *backend = rangefinder.get_backend(i); + if (backend == nullptr) { + continue; + } + + RangeFinder::Status status = backend->status(); + if (status <= RangeFinder::Status::NoData) { + // don't send any data for this instance + continue; + } + + const uint32_t sample_ms = backend->last_reading_ms(); + if (last_rangefinder_sample_ms[i] == sample_ms) { + // don't same the same reading again + continue; + } + last_rangefinder_sample_ms[i] = sample_ms; + + uavcan_equipment_range_sensor_Measurement pkt {}; + pkt.sensor_id = rangefinder.get_address(i); + + switch (status) { + case RangeFinder::Status::OutOfRangeLow: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_CLOSE; + break; + case RangeFinder::Status::OutOfRangeHigh: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; + break; + case RangeFinder::Status::Good: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; + break; + default: + pkt.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_UNDEFINED; + break; + } + + switch (backend->get_mav_distance_sensor_type()) { + case MAV_DISTANCE_SENSOR_LASER: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR; + break; + case MAV_DISTANCE_SENSOR_ULTRASOUND: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_SONAR; + break; + case MAV_DISTANCE_SENSOR_RADAR: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_RADAR; + break; + default: + pkt.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_UNDEFINED; + break; + } - uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_range_sensor_Measurement_encode(&pkt, buffer, !periph.canfdout()); + float dist_m = backend->distance(); + pkt.range = dist_m; - canard_broadcast(UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SIGNATURE, - UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); + uint8_t buffer[UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_MAX_SIZE] {}; + uint16_t total_size = uavcan_equipment_range_sensor_Measurement_encode(&pkt, buffer, !periph.canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SIGNATURE, + UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + + } } #endif // HAL_PERIPH_ENABLE_RANGEFINDER diff --git a/Tools/AP_Periph/rpm.cpp b/Tools/AP_Periph/rpm.cpp new file mode 100644 index 0000000000000..5a39866013b7e --- /dev/null +++ b/Tools/AP_Periph/rpm.cpp @@ -0,0 +1,55 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + +#include + +// Send rpm message occasionally +void AP_Periph_FW::rpm_sensor_send(void) +{ + if (g.rpm_msg_rate <= 0) { + return; + } + + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - rpm_last_send_ms < (1000U / g.rpm_msg_rate)) { + return; + } + rpm_last_send_ms = now_ms; + + { + const uint8_t num_sensors = rpm_sensor.num_sensors(); + for (uint8_t i = 0; i < num_sensors; i++) { + // Send each sensor in turn + const uint8_t index = (rpm_last_sent_index + 1 + i) % num_sensors; + + const int8_t sensor_id = rpm_sensor.get_dronecan_sensor_id(index); + if (sensor_id < 0) { + // disabled or not configured to send + continue; + } + + dronecan_sensors_rpm_RPM pkt {}; + pkt.sensor_id = sensor_id; + + // Get rpm and set health flag + if (!rpm_sensor.get_rpm(index, pkt.rpm)) { + pkt.flags |= DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY; + } + + uint8_t buffer[DRONECAN_SENSORS_RPM_RPM_MAX_SIZE] {}; + const uint16_t total_size = dronecan_sensors_rpm_RPM_encode(&pkt, buffer, !canfdout()); + + canard_broadcast(DRONECAN_SENSORS_RPM_RPM_SIGNATURE, + DRONECAN_SENSORS_RPM_RPM_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + + rpm_last_sent_index = index; + break; + } + } +} + +#endif // HAL_PERIPH_ENABLE_RPM_STREAM diff --git a/Tools/AP_Periph/serial_tunnel.cpp b/Tools/AP_Periph/serial_tunnel.cpp index cdba23b41c46d..6a99126980250 100644 --- a/Tools/AP_Periph/serial_tunnel.cpp +++ b/Tools/AP_Periph/serial_tunnel.cpp @@ -50,7 +50,7 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER if (uart_num == -1) { - uart_num = g.rangefinder_port; + uart_num = g.rangefinder_port[0]; } #endif #ifdef HAL_PERIPH_ENABLE_ADSB diff --git a/Tools/Frame_params/SPARKKit-rover.param b/Tools/Frame_params/SPARKKit-rover.param new file mode 100644 index 0000000000000..bb8cd8f1afdf9 --- /dev/null +++ b/Tools/Frame_params/SPARKKit-rover.param @@ -0,0 +1,57 @@ +#NOTE: Params for SPARTK Kit Rover V4.5.0 (and higher) +ACRO_TURN_RATE,90 +AHRS_ORIENTATION,14 +ATC_SPEED_I,0.7556667 +ATC_SPEED_P,0.7556667 +ATC_STR_ACC_MAX,160 +ATC_STR_RAT_D,0.002 +ATC_STR_RAT_FF,0.3316459 +ATC_STR_RAT_FLTD,2 +ATC_STR_RAT_FLTT,2 +ATC_STR_RAT_I,0.17 +ATC_STR_RAT_P,0.17 +ATC_TURN_MAX_G,0.15 +BATT_CURR_PIN,15 +BATT_VOLT_MULT,12.02 +BATT_VOLT_PIN,14 +CAN_P1_DRIVER,1 +COMPASS_USE2,0 +COMPASS_USE3,0 +CRUISE_SPEED,1.137718 +CRUISE_THROTTLE,85 +EK3_IMU_MASK,7 +FRAME_CLASS,1 +FRAME_TYPE,0 +FS_CRASH_CHECK,2 +FS_EKF_THRESH,0.6 +FS_GCS_TIMEOUT,2 +FS_THR_ENABLE,2 +GPS_POS1_X,-0.1 +GPS_POS1_Y,-0.08 +GPS_TYPE,9 +GUID_OPTIONS,64 +MANUAL_OPTIONS,1 +MANUAL_STR_EXPO,0.2 +MODE_CH,5 +MODE3,0 +MODE4,1 +MODE5,0 +MODE6,10 +MOT_THR_MIN,14 +NTF_LED_LEN,16 +NTF_LED_TYPES,123367 +PSC_VEL_D,0.02 +PSC_VEL_FF,1 +PSC_VEL_I,0.04 +PSC_VEL_P,0.2 +SERIAL1_BAUD,921 +SERVO1_MAX,1920 +SERVO1_MIN,1120 +SERVO1_TRIM,1538 +SERVO3_MAX,1920 +SERVO3_MIN,1120 +SERVO3_TRIM,1520 +SERVO9_FUNCTION,120 +WP_PIVOT_ANGLE,0 +WP_PIVOT_RATE,0 +WP_SPEED,1 diff --git a/Tools/Frame_params/hexsoon-edu650.param b/Tools/Frame_params/hexsoon-edu650.param index 330ffba32feed..cd3e08251612f 100644 --- a/Tools/Frame_params/hexsoon-edu650.param +++ b/Tools/Frame_params/hexsoon-edu650.param @@ -17,8 +17,6 @@ ATC_RAT_RLL_P,0.10 ATC_RAT_YAW_FLTD,10 ATC_RAT_YAW_FLTE,2 ATC_RAT_YAW_FLTT,10 -BATT_MONITOR,3 -BATT_VOLT_MULT,12.02 FRAME_CLASS,1 FRAME_TYPE,1 INS_GYRO_FILTER,40 diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin index 5934290788ad0..45354a76ef356 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..a7e29528d9ff5 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..62564b2c04a24 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..be0a4ac44d015 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..afdd37a688b32 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..6757005343408 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..b14b7183293e1 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..411152646d4e7 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..b094ccf1a9b35 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..6837e06288055 100755 Binary files a/Tools/IO_Firmware/iofirmware_lowpolh.bin and b/Tools/IO_Firmware/iofirmware_lowpolh.bin differ diff --git a/Tools/Replay/wscript b/Tools/Replay/wscript index 936707364ec84..0e3b9c28ba508 100644 --- a/Tools/Replay/wscript +++ b/Tools/Replay/wscript @@ -17,9 +17,6 @@ def build(bld): name=vehicle + '_libs', ap_vehicle=vehicle, ap_libraries=bld.ap_common_vehicle_libraries() + [ - 'AP_Beacon', - 'AP_Arming', - 'AP_RCMapper', 'AP_OSD', 'AP_Avoidance', ], diff --git a/Tools/ardupilotwaf/ap_library.py b/Tools/ardupilotwaf/ap_library.py index 67cb61428248b..1dc690fece9e2 100644 --- a/Tools/ardupilotwaf/ap_library.py +++ b/Tools/ardupilotwaf/ap_library.py @@ -206,6 +206,8 @@ def scan(self): # force dependency scan, if necessary self.compiled_task.signature() + if not self.compiled_task.uid() in self.generator.bld.node_deps: + return r, [] for n in self.generator.bld.node_deps[self.compiled_task.uid()]: # using common Node methods doesn't work here p = n.abspath() diff --git a/Tools/ardupilotwaf/ardupilotwaf.py b/Tools/ardupilotwaf/ardupilotwaf.py index 8f17317b738e1..d20eef7e50c60 100644 --- a/Tools/ardupilotwaf/ardupilotwaf.py +++ b/Tools/ardupilotwaf/ardupilotwaf.py @@ -118,6 +118,9 @@ 'AP_CheckFirmware', 'AP_ExternalControl', 'AP_JSON', + 'AP_Beacon', + 'AP_Arming', + 'AP_RCMapper', ] def get_legacy_defines(sketch_name, bld): diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 9b6824fc67679..b25591523afaf 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -433,9 +433,14 @@ def configure_env(self, cfg, env): ] if cfg.env.DEST_OS == 'darwin': - env.LINKFLAGS += [ - '-Wl,-dead_strip', - ] + if self.cc_version_gte(cfg, 15, 0): + env.LINKFLAGS += [ + '-Wl,-dead_strip,-ld_classic', + ] + else: + env.LINKFLAGS += [ + '-Wl,-dead_strip', + ] else: env.LINKFLAGS += [ '-fno-exceptions', @@ -537,6 +542,14 @@ def embed_ROMFS_files(self, ctx): if not embed.create_embedded_h(header, ctx.env.ROMFS_FILES, ctx.env.ROMFS_UNCOMPRESSED): ctx.fatal("Failed to created ap_romfs_embedded.h") + ctx.env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_H'] + + # Allow lua to load from ROMFS if any lua files are added + for file in ctx.env.ROMFS_FILES: + if file[0].startswith("scripts") and file[0].endswith(".lua"): + ctx.env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_LUA'] + break + Board = BoardMeta('Board', Board.__bases__, dict(Board.__dict__)) def add_dynamic_boards_chibios(): @@ -772,14 +785,6 @@ def configure_env(self, cfg, env): if fnmatch.fnmatch(f, "*.lua"): env.ROMFS_FILES += [('scripts/'+f,'ROMFS/scripts/'+f)] - if len(env.ROMFS_FILES) > 0: - # Allow lua to load from ROMFS if any lua files are added - for file in env.ROMFS_FILES: - if file[0].startswith("scripts") and file[0].endswith(".lua"): - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_LUA'] - break - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_H'] - if cfg.options.sitl_rgbled: env.CXXFLAGS += ['-DWITH_SITL_RGBLED'] @@ -915,6 +920,7 @@ def configure_env(self, cfg, env): HAL_PERIPH_ENABLE_BATTERY = 1, HAL_PERIPH_ENABLE_EFI = 1, HAL_PERIPH_ENABLE_RPM = 1, + HAL_PERIPH_ENABLE_RPM_STREAM = 1, HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1, @@ -1351,13 +1357,6 @@ def configure_env(self, cfg, env): env.DEFINES.update( HAL_PARAM_DEFAULTS_PATH='"@ROMFS/defaults.parm"', ) - if len(env.ROMFS_FILES) > 0: - # Allow lua to load from ROMFS if any lua files are added - for file in env.ROMFS_FILES: - if file[0].startswith("scripts") and file[0].endswith(".lua"): - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_LUA'] - break - env.CXXFLAGS += ['-DHAL_HAVE_AP_ROMFS_EMBEDDED_H'] def build(self, bld): super(linux, self).build(bld) diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 532e75a4b3a33..4f1e7a8626d0c 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -19,7 +19,11 @@ _dynamic_env_data = {} def _load_dynamic_env_data(bld): bldnode = bld.bldnode.make_node('modules/ChibiOS') - tmp_str = bldnode.find_node('include_dirs').read() + include_dirs_node = bldnode.find_node('include_dirs') + if include_dirs_node is None: + _dynamic_env_data['include_dirs'] = [] + return + tmp_str = include_dirs_node.read() tmp_str = tmp_str.replace(';\n','') tmp_str = tmp_str.replace('-I','') #remove existing -I flags # split, coping with separator @@ -257,8 +261,13 @@ def sign_firmware(image, private_keyfile): try: import monocypher except ImportError: - Logs.error("Please install monocypher with: python3 -m pip install pymonocypher") + Logs.error("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") + return None + + if monocypher.__version__ != "3.1.3.2": + Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2") return None + try: key = open(private_keyfile, 'r').read() except Exception as ex: diff --git a/Tools/ardupilotwaf/git_submodule.py b/Tools/ardupilotwaf/git_submodule.py index be28216e9c114..e2c727e05bb97 100644 --- a/Tools/ardupilotwaf/git_submodule.py +++ b/Tools/ardupilotwaf/git_submodule.py @@ -91,7 +91,7 @@ def runnable_status(self): else: r = Task.RUN_ME - if self.non_fast_forward: + if getattr(self,'non_fast_forward',[]): r = Task.SKIP_ME return r @@ -148,7 +148,7 @@ def git_submodule(bld, git_submodule, **kw): def _post_fun(bld): Logs.info('') for name, t in _submodules_tasks.items(): - if not t.non_fast_forward: + if not getattr(t,'non_fast_forward',[]): continue Logs.warn("Submodule %s not updated: non-fastforward" % name) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 5a818ea7ef64b..56ece1f7ed5d3 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -26,6 +26,7 @@ from vehicle_test_suite import Test from vehicle_test_suite import MAV_POS_TARGET_TYPE_MASK from vehicle_test_suite import WaitAndMaintainArmed +from vehicle_test_suite import WaitModeTimeout from pymavlink.rotmat import Vector3 @@ -1603,6 +1604,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''' @@ -3125,9 +3178,10 @@ def MotorVibration(self): psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) # ignore the first 20Hz and look for a peak at -15dB or more - ignore_bins = 20 + # it should be at about 190Hz, each bin is 1000/1024Hz wide + ignore_bins = int(100 * 1.024) # start at 100Hz to be safe freq = psd["F"][numpy.argmax(psd["X"][ignore_bins:]) + ignore_bins] - if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 180 or freq > 300: + if numpy.amax(psd["X"][ignore_bins:]) < -15 or freq < 100 or freq > 300: raise NotAchievedException( "Did not detect a motor peak, found %f at %f dB" % (freq, numpy.amax(psd["X"][ignore_bins:]))) @@ -3726,7 +3780,7 @@ def WPNAV_SPEED_DN(self): minimum_duration = 5 - self.takeoff(500, timeout=60) + self.takeoff(500, timeout=70) self.change_mode('AUTO') start_speed_ms = self.get_parameter('WPNAV_SPEED_DN') / 100.0 @@ -5845,8 +5899,8 @@ def ThrowMode(self): (tdelta, max_good_tdelta)) self.progress("Vehicle returned") - def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, - reverse=None, takeoff=True): + def hover_and_check_matched_frequency_with_fft_and_psd(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, + reverse=None, takeoff=True, instance=0): # find a motor peak if takeoff: self.takeoff(10, mode="ALT_HOLD") @@ -5854,7 +5908,7 @@ def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, max tstart, tend, hover_throttle = self.hover_for_interval(15) self.do_RTL() - psd = self.mavfft_fttd(1, 0, tstart * 1.0e6, tend * 1.0e6) + psd = self.mavfft_fttd(1, instance, tstart * 1.0e6, tend * 1.0e6) # batch sampler defaults give 1024 fft and sample rate of 1kz so roughly 1hz/bin freq = psd["F"][numpy.argmax(psd["X"][minhz:maxhz]) + minhz] * (1000. / 1024.) @@ -5873,8 +5927,34 @@ def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, max self.progress("Detected motor peak at %fHz, throttle %f%%, %fdB" % (freq, hover_throttle, peakdb)) + return freq, hover_throttle, peakdb, psd + + def hover_and_check_matched_frequency_with_fft(self, dblevel=-15, minhz=200, maxhz=300, peakhz=None, + reverse=None, takeoff=True, instance=0): + freq, hover_throttle, peakdb, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(dblevel, minhz, + maxhz, peakhz, reverse, takeoff, instance) return freq, hover_throttle, peakdb + def get_average_esc_frequency(self): + mlog = self.dfreader_for_current_onboard_log() + rpm_total = 0 + rpm_count = 0 + tho = 0 + while True: + m = mlog.recv_match() + if m is None: + break + msg_type = m.get_type() + if msg_type == "CTUN": + tho = m.ThO + elif msg_type == "ESC" and tho > 0.1: + rpm_total += m.RPM + rpm_count += 1 + + esc_hz = rpm_total / (rpm_count * 60) + return esc_hz + def DynamicNotches(self): """Use dynamic harmonic notch to control motor noise.""" self.progress("Flying with dynamic notches") @@ -5911,13 +5991,15 @@ def DynamicNotches(self): }) self.reboot_sitl() - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + freq, hover_throttle, peakdb1 = \ + self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) # now add double dynamic notches and check that the peak is squashed self.set_parameter("INS_HNTCH_OPTS", 1) self.reboot_sitl() - freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2 = \ + self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) # double-notch should do better, but check for within 5% if peakdb2 * 1.05 > peakdb1: @@ -5929,7 +6011,8 @@ def DynamicNotches(self): self.set_parameter("INS_HNTCH_OPTS", 16) self.reboot_sitl() - freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2 = \ + self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) # triple-notch should do better, but check for within 5% if peakdb2 * 1.05 > peakdb1: @@ -5955,7 +6038,7 @@ def DynamicRpmNotches(self): "AHRS_EKF_TYPE": 10, "INS_LOG_BAT_MASK": 3, "INS_LOG_BAT_OPT": 0, - "INS_GYRO_FILTER": 100, # set gyro filter high so we can observe behaviour + "INS_GYRO_FILTER": 300, # set gyro filter high so we can observe behaviour "LOG_BITMASK": 958, "LOG_DISARMED": 0, "SIM_VIB_MOT_MAX": 350, @@ -5966,12 +6049,14 @@ def DynamicRpmNotches(self): self.takeoff(10, mode="ALT_HOLD") - # find a motor peak - freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-15, 200, 300) + # find a motor peak, the peak is at about 190Hz, so checking between 50 and 320Hz should be safe. + # there is a second harmonic at 380Hz which should be avoided to make the test reliable + # detect at -5dB so we don't pick some random noise as the peak. The actual peak is about +15dB + freq, hover_throttle, peakdb = self.hover_and_check_matched_frequency_with_fft(-5, 50, 320) # now add a dynamic notch and check that the peak is squashed self.set_parameters({ - "INS_LOG_BAT_OPT": 2, + "INS_LOG_BAT_OPT": 4, "INS_HNTCH_ENABLE": 1, "INS_HNTCH_FREQ": 80, "INS_HNTCH_REF": 1.0, @@ -5982,19 +6067,34 @@ def DynamicRpmNotches(self): }) self.reboot_sitl() - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + # -10dB is pretty conservative - actual is about -25dB + freq, hover_throttle, peakdb1, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-10, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb1 = psd["X"][int(esc_hz)] # now add notch-per motor and check that the peak is squashed self.set_parameter("INS_HNTCH_OPTS", 2) self.reboot_sitl() - freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-10, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb2 = psd["X"][int(esc_hz)] - # notch-per-motor should do better, but check for within 10%. ( its mostly within 5%, but does vary a bit) - if peakdb2 * 1.10 > peakdb1: + # notch-per-motor will be better at the average ESC frequency + if esc_peakdb2 > esc_peakdb1: raise NotAchievedException( "Notch-per-motor peak was higher than single-notch peak %fdB > %fdB" % - (peakdb2, peakdb1)) + (esc_peakdb2, esc_peakdb1)) + + # check that the noise is being squashed at all. this needs to be an aggresive check so that failure happens easily + # testing shows this to be -58dB on average + if esc_peakdb2 > -25: + raise NotAchievedException( + "Notch-per-motor had a peak of %fdB there should be none" % esc_peakdb2) # Now do it again for an octacopter self.context_push() @@ -6007,20 +6107,29 @@ def DynamicRpmNotches(self): defaults_filepath=','.join(self.model_defaults_filepath("octa")), model="octa" ) - freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(-10, 20, 350, reverse=True) + freq, hover_throttle, peakdb1, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-10, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb1 = psd["X"][int(esc_hz)] # now add notch-per motor and check that the peak is squashed self.set_parameter("INS_HNTCH_HMNCS", 1) self.set_parameter("INS_HNTCH_OPTS", 2) self.reboot_sitl() - freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) + freq, hover_throttle, peakdb2, psd = \ + self.hover_and_check_matched_frequency_with_fft_and_psd(-15, 50, 320, reverse=True, instance=2) + # find the noise at the motor frequency + esc_hz = self.get_average_esc_frequency() + esc_peakdb2 = psd["X"][int(esc_hz)] - # notch-per-motor should do better, but check for within 5% - if peakdb2 * 1.05 > peakdb1: + # notch-per-motor will be better at the average ESC frequency + if esc_peakdb2 > esc_peakdb1: raise NotAchievedException( "Notch-per-motor peak was higher than single-notch peak %fdB > %fdB" % - (peakdb2, peakdb1)) + (esc_peakdb2, esc_peakdb1)) + except Exception as e: self.print_exception_caught(e) ex = e @@ -7047,57 +7156,39 @@ def PosHoldTakeOff(self): """ensure vehicle stays put until it is ready to fly""" self.context_push() - ex = None - try: - self.set_parameter("PILOT_TKOFF_ALT", 700) - self.change_mode('POSHOLD') - self.set_rc(3, 1000) - self.wait_ready_to_arm() - self.arm_vehicle() - self.delay_sim_time(2) - # check we are still on the ground... - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - if abs(m.relative_alt) > 100: - raise NotAchievedException("Took off prematurely") - - self.progress("Pushing throttle up") - self.set_rc(3, 1710) - self.delay_sim_time(0.5) - self.progress("Bringing back to hover throttle") - self.set_rc(3, 1500) + self.set_parameter("PILOT_TKOFF_ALT", 700) + self.change_mode('POSHOLD') + self.set_rc(3, 1000) + self.wait_ready_to_arm() + self.arm_vehicle() + self.delay_sim_time(2) + # check we are still on the ground... + relative_alt = self.get_altitude(relative=True) + if relative_alt > 0.1: + raise NotAchievedException("Took off prematurely") - # make sure we haven't already reached alt: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - max_initial_alt = 2000 - if abs(m.relative_alt) > max_initial_alt: - raise NotAchievedException("Took off too fast (%f > %f" % - (abs(m.relative_alt), max_initial_alt)) + self.progress("Pushing throttle up") + self.set_rc(3, 1710) + self.delay_sim_time(0.5) + self.progress("Bringing back to hover throttle") + self.set_rc(3, 1500) - self.progress("Monitoring takeoff-to-alt") - self.wait_altitude(6.9, 8, relative=True) + # make sure we haven't already reached alt: + relative_alt = self.get_altitude(relative=True) + max_initial_alt = 2.0 + if abs(relative_alt) > max_initial_alt: + raise NotAchievedException("Took off too fast (%f > %f" % + (relative_alt, max_initial_alt)) - self.progress("Making sure we stop at our takeoff altitude") - tstart = self.get_sim_time() - while self.get_sim_time() - tstart < 5: - m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) - delta = abs(7000 - m.relative_alt) - self.progress("alt=%f delta=%f" % (m.relative_alt/1000, - delta/1000)) - if delta > 1000: - raise NotAchievedException("Failed to maintain takeoff alt") - self.progress("takeoff OK") - except Exception as e: - self.print_exception_caught(e) - ex = e + self.progress("Monitoring takeoff-to-alt") + self.wait_altitude(6.9, 8, relative=True, minimum_duration=10) + self.progress("takeoff OK") self.land_and_disarm() self.set_rc(8, 1000) self.context_pop() - if ex is not None: - raise ex - def initial_mode(self): return "STABILIZE" @@ -7652,7 +7743,8 @@ def BaroWindCorrection(self): ex = None try: self.customise_SITL_commandline( - ["--defaults", ','.join(self.model_defaults_filepath('Callisto'))], + [], + defaults_filepath=self.model_defaults_filepath('Callisto'), model="octa-quad:@ROMFS/models/Callisto.json", wipe=True, ) @@ -8769,7 +8861,7 @@ def test_replay_optical_flow_bit(self): print("log difference: %s" % str(log_difference)) return log_difference[0] - def GPSBlending(self): + def GPSBlendingLog(self): '''Test GPS Blending''' '''ensure we get dataflash log messages for blended instance''' @@ -8844,10 +8936,141 @@ def GPSBlending(self): if ex is not None: raise ex + def GPSBlending(self): + '''Test GPS Blending''' + '''ensure we get dataflash log messages for blended instance''' + + self.context_push() + + # configure: + self.set_parameters({ + "WP_YAW_BEHAVIOR": 0, # do not yaw + "GPS2_TYPE": 1, + "SIM_GPS2_TYPE": 1, + "SIM_GPS2_DISABLE": 0, + "SIM_GPS_POS_X": 1.0, + "SIM_GPS_POS_Y": -1.0, + "SIM_GPS2_POS_X": -1.0, + "SIM_GPS2_POS_Y": 1.0, + "GPS_AUTO_SWITCH": 2, + }) + self.reboot_sitl() + + alt = 10 + self.takeoff(alt, mode='GUIDED') + self.fly_guided_move_local(30, 0, alt) + self.fly_guided_move_local(30, 30, alt) + self.fly_guided_move_local(0, 30, alt) + self.fly_guided_move_local(0, 0, alt) + self.change_mode('LAND') + + current_log_file = self.dfreader_for_current_onboard_log() + + self.wait_disarmed() + + # ensure that the blended solution is always about half-way + # between the two GPSs: + current_ts = None + while True: + m = current_log_file.recv_match(type='GPS') + if m is None: + break + if current_ts is None: + if m.I != 0: # noqa + continue + current_ts = m.TimeUS + measurements = {} + if m.TimeUS != current_ts: + current_ts = None + continue + measurements[m.I] = (m.Lat, m.Lng) + if len(measurements) == 3: + # check lat: + for n in 0, 1: + expected_blended = (measurements[0][n] + measurements[1][n])/2 + epsilon = 0.0000002 + error = abs(measurements[2][n] - expected_blended) + if error > epsilon: + raise NotAchievedException("Blended diverged") + current_ts = None + + self.context_pop() + self.reboot_sitl() + + def GPSWeightedBlending(self): + '''Test GPS Weighted Blending''' + + self.context_push() + + # configure: + self.set_parameters({ + "WP_YAW_BEHAVIOR": 0, # do not yaw + "GPS2_TYPE": 1, + "SIM_GPS2_TYPE": 1, + "SIM_GPS2_DISABLE": 0, + "SIM_GPS_POS_X": 1.0, + "SIM_GPS_POS_Y": -1.0, + "SIM_GPS2_POS_X": -1.0, + "SIM_GPS2_POS_Y": 1.0, + "GPS_AUTO_SWITCH": 2, + }) + # configure velocity errors such that the 1st GPS should be + # 4/5, second GPS 1/5 of result (0.5**2)/((0.5**2)+(1.0**2)) + self.set_parameters({ + "SIM_GPS_VERR_X": 0.3, # m/s + "SIM_GPS_VERR_Y": 0.4, + "SIM_GPS2_VERR_X": 0.6, # m/s + "SIM_GPS2_VERR_Y": 0.8, + "GPS_BLEND_MASK": 4, # use only speed for blend calculations + }) + self.reboot_sitl() + + alt = 10 + self.takeoff(alt, mode='GUIDED') + self.fly_guided_move_local(30, 0, alt) + self.fly_guided_move_local(30, 30, alt) + self.fly_guided_move_local(0, 30, alt) + self.fly_guided_move_local(0, 0, alt) + self.change_mode('LAND') + + current_log_file = self.dfreader_for_current_onboard_log() + + self.wait_disarmed() + + # ensure that the blended solution is always about half-way + # between the two GPSs: + current_ts = None + while True: + m = current_log_file.recv_match(type='GPS') + if m is None: + break + if current_ts is None: + if m.I != 0: # noqa + continue + current_ts = m.TimeUS + measurements = {} + if m.TimeUS != current_ts: + current_ts = None + continue + measurements[m.I] = (m.Lat, m.Lng) + if len(measurements) == 3: + # check lat: + for n in 0, 1: + expected_blended = 0.8*measurements[0][n] + 0.2*measurements[1][n] + epsilon = 0.0000002 + error = abs(measurements[2][n] - expected_blended) + if error > epsilon: + raise NotAchievedException(f"Blended diverged {measurements[0][n]=} {measurements[1][n]=}") + current_ts = None + + self.context_pop() + self.reboot_sitl() + def Callisto(self): '''Test Callisto''' self.customise_SITL_commandline( - ["--defaults", ','.join(self.model_defaults_filepath('Callisto')), ], + [], + defaults_filepath=self.model_defaults_filepath('Callisto'), model="octa-quad:@ROMFS/models/Callisto.json", wipe=True, ) @@ -8881,12 +9104,12 @@ def FlyEachFrame(self): # the model string for Callisto has crap in it.... we # should really have another entry in the vehicleinfo data # to carry the path to the JSON. - actual_model = model.split(":")[0] - defaults = self.model_defaults_filepath(actual_model) + defaults = self.model_defaults_filepath(frame) if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( - ["--defaults", ','.join(defaults), ], + [], + defaults_filepath=defaults, model=model, wipe=True, ) @@ -10203,6 +10426,7 @@ def tests1d(self): self.HorizontalFence, self.HorizontalAvoidFence, self.MaxAltFence, + self.MaxAltFenceAvoid, self.MinAltFence, self.FenceFloorEnabledLanding, self.AutoTuneSwitch, @@ -10925,13 +11149,167 @@ def GuidedModeThrust(self): self.wait_altitude(0.5, 100, relative=True, timeout=10) self.do_RTL() + def AutoRTL(self): + '''Test Auto RTL mode using do land start and return path start mission items''' + alt = 50 + guided_loc = self.home_relative_loc_ne(1000, 0) + guided_loc.alt += alt + + # Arm, take off and fly to guided location + self.takeoff(mode='GUIDED') + self.fly_guided_move_to(guided_loc, timeout=240) + + # Try auto RTL mode, should fail with no mission + try: + self.change_mode('AUTO_RTL', timeout=10) + raise NotAchievedException("Should not change mode with no mission") + except WaitModeTimeout: + pass + except Exception as e: + raise e + + # pymavlink does not understand the new return path command yet, at some point it will + cmd_return_path_start = 188 # mavutil.mavlink.MAV_CMD_DO_RETURN_PATH_START + + # Do land start and do return path should both fail as commands too + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # Load mission with do land start + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, alt), # 1 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 750, 0, alt), # 2 + self.create_MISSION_ITEM_INT(mavutil.mavlink.MAV_CMD_DO_LAND_START), # 3 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, alt), # 4 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 250, 0, alt), # 5 + ]) + + # Return path should still fail + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # Do land start should jump to the waypoint following the item + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(4) + + # Back to guided location + self.change_mode('GUIDED') + self.fly_guided_move_to(guided_loc) + + # mode change to Auto RTL should do the same + self.change_mode('AUTO_RTL') + self.drain_mav() + self.assert_current_waypoint(4) + + # Back to guided location + self.change_mode('GUIDED') + self.fly_guided_move_to(guided_loc) + + # Add a return path item + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1250, 0, alt), # 1 + self.create_MISSION_ITEM_INT(cmd_return_path_start), # 2 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 900, 0, alt), # 3 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 750, 0, alt), # 4 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 550, 0, alt), # 5 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 500, 0, alt), # 6 + self.create_MISSION_ITEM_INT(mavutil.mavlink.MAV_CMD_DO_LAND_START), # 7 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 250, 0, alt), # 8 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -250, 0, alt), # 9 + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, -500, 0, alt), # 10 + ]) + + # Return path should now work + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(3) + + # Back to guided location + self.change_mode('GUIDED') + self.fly_guided_move_to(guided_loc) + + # mode change to Auto RTL should join the return path + self.change_mode('AUTO_RTL') + self.drain_mav() + self.assert_current_waypoint(3) + + # do land start should still work + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(8) + + # Move a bit closer in guided + return_path_test = self.home_relative_loc_ne(600, 0) + return_path_test.alt += alt + self.change_mode('GUIDED') + self.fly_guided_move_to(return_path_test, timeout=100) + + # check the mission is joined further along + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(5) + + # fly over home + home = self.home_relative_loc_ne(0, 0) + home.alt += alt + self.change_mode('GUIDED') + self.fly_guided_move_to(home, timeout=140) + + # Should never join return path after do land start + self.run_cmd(cmd_return_path_start, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + self.drain_mav() + self.assert_current_waypoint(6) + + # Done + self.land_and_disarm() + + def EK3_OGN_HGT_MASK(self): + '''test baraometer-alt-compensation based on long-term GPS readings''' + self.context_push() + self.set_parameters({ + 'EK3_OGN_HGT_MASK': 1, # compensate baro drift using GPS + }) + self.reboot_sitl() + + expected_alt = 10 + + self.change_mode('GUIDED') + self.wait_ready_to_arm() + current_alt = self.get_altitude() + + expected_alt_abs = current_alt + expected_alt + + self.takeoff(expected_alt, mode='GUIDED') + self.delay_sim_time(5) + + self.set_parameter("SIM_BARO_DRIFT", 0.01) # 1cm/second + + def check_altitude(mav, m): + m_type = m.get_type() + epsilon = 10 # in metres + if m_type == 'GPS_RAW_INT': + got_gps_alt = m.alt * 0.001 + if abs(expected_alt_abs - got_gps_alt) > epsilon: + raise NotAchievedException(f"Bad GPS altitude (got={got_gps_alt} want={expected_alt_abs})") + elif m_type == 'GLOBAL_POSITION_INT': + got_canonical_alt = m.relative_alt * 0.001 + if abs(expected_alt - got_canonical_alt) > epsilon: + raise NotAchievedException(f"Bad canonical altitude (got={got_canonical_alt} want={expected_alt})") + + self.install_message_hook_context(check_altitude) + + self.delay_sim_time(1500) + + self.context_pop() + self.reboot_sitl(force=True) + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ self.MotorVibration, Test(self.DynamicNotches, attempts=4), self.PositionWhenGPSIsZero, - Test(self.DynamicRpmNotches, attempts=4), + self.DynamicRpmNotches, # Do not add attempts to this - failure is sign of a bug self.PIDNotches, self.RefindGPS, Test(self.GyroFFT, attempts=1, speedup=8), @@ -10952,6 +11330,8 @@ def tests2b(self): # this block currently around 9.5mins here self.RTL_TO_RALLY, self.FlyEachFrame, self.GPSBlending, + self.GPSWeightedBlending, + self.GPSBlendingLog, self.DataFlash, Test(self.DataFlashErase, attempts=8), self.Callisto, @@ -11006,6 +11386,8 @@ def tests2b(self): # this block currently around 9.5mins here self.LoiterToGuidedHomeVSOrigin, self.GuidedModeThrust, self.CompassMot, + self.AutoRTL, + self.EK3_OGN_HGT_MASK, ]) return ret @@ -11036,7 +11418,6 @@ def disabled_tests(self): "GroundEffectCompensation_touchDownExpected": "Flapping", "FlyMissionTwice": "See https://github.com/ArduPilot/ardupilot/pull/18561", "GPSForYawCompassLearn": "Vehicle currently crashed in spectacular fashion", - "GuidedModeThrust": "land detector raises internal error as we're not saying we're about to take off but just did", "CompassMot": "Cuases an arithmetic exception in the EKF", } diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index e0382402528d0..b05f565a5a298 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -3013,7 +3013,7 @@ def record_maxalt(mav, m): if m.relative_alt/1000.0 > max_alt: max_alt = m.relative_alt/1000.0 - self.install_message_hook(record_maxalt) + self.install_message_hook_context(record_maxalt) self.fly_mission_waypoints(num_wp-1, mission_timeout=600) @@ -3104,7 +3104,7 @@ def TerrainLoiter(self): self.fly_home_land_and_disarm(240) def fly_external_AHRS(self, sim, eahrs_type, mission): - """Fly with external AHRS (VectorNav)""" + """Fly with external AHRS""" self.customise_SITL_commandline(["--serial4=sim:%s" % sim]) self.set_parameters({ @@ -3228,6 +3228,55 @@ def InertialLabsEAHRS(self): '''Test InertialLabs EAHRS support''' self.fly_external_AHRS("ILabs", 5, "ap1.txt") + def GpsSensorPreArmEAHRS(self): + '''Test pre-arm checks related to EAHRS_SENSORS using the MicroStrain7 driver''' + self.customise_SITL_commandline(["--serial4=sim:MicroStrain7"]) + + self.set_parameters({ + "EAHRS_TYPE": 7, + "SERIAL4_PROTOCOL": 36, + "SERIAL4_BAUD": 230400, + "GPS1_TYPE": 0, # Disabled (simulate user setup error) + "GPS2_TYPE": 0, # Disabled (simulate user setup error) + "AHRS_EKF_TYPE": 11, + "INS_GYR_CAL": 1, + "EAHRS_SENSORS": 13, # GPS is enabled + }) + self.reboot_sitl() + self.delay_sim_time(5) + self.progress("Running accelcal") + self.run_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=4, + timeout=5, + ) + + self.assert_prearm_failure("ExternalAHRS: Incorrect number", # Cut short due to message limits. + timeout=30, + other_prearm_failures_fatal=False) + + self.set_parameters({ + "EAHRS_TYPE": 7, + "SERIAL4_PROTOCOL": 36, + "SERIAL4_BAUD": 230400, + "GPS1_TYPE": 1, # Auto + "GPS2_TYPE": 21, # EARHS + "AHRS_EKF_TYPE": 11, + "INS_GYR_CAL": 1, + "EAHRS_SENSORS": 13, # GPS is enabled + }) + self.reboot_sitl() + self.delay_sim_time(5) + self.progress("Running accelcal") + self.run_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=4, + timeout=5, + ) + # Check prearm success with MicroStrain when the first GPS is occupied by another GPS. + # This supports the use case of comparing MicroStrain dual antenna to another GPS. + self.wait_ready_to_arm() + def get_accelvec(self, m): return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81 @@ -3896,6 +3945,8 @@ def FlyEachFrame(self): "plane-ice" : "needs ICE control channel for ignition", "quadplane-ice" : "needs ICE control channel for ignition", "quadplane-can" : "needs CAN periph", + "stratoblimp" : "not expected to fly normally", + "glider" : "needs balloon lift", } for frame in sorted(vinfo_options["frames"].keys()): self.start_subtest("Testing frame (%s)" % str(frame)) @@ -3917,7 +3968,8 @@ def FlyEachFrame(self): if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( - ["--defaults", ','.join(defaults), ], + [], + defaults_filepath=defaults, model=model, wipe=True, ) @@ -5343,6 +5395,7 @@ def tests(self): self.MicroStrainEAHRS5, self.MicroStrainEAHRS7, self.InertialLabsEAHRS, + self.GpsSensorPreArmEAHRS, self.Deadreckoning, self.DeadreckoningNoAirSpeed, self.EKFlaneswitch, diff --git a/Tools/autotest/default_params/copter-X.parm b/Tools/autotest/default_params/copter-X.parm index ee06ded19b212..06081beef07ee 100644 --- a/Tools/autotest/default_params/copter-X.parm +++ b/Tools/autotest/default_params/copter-X.parm @@ -1,3 +1 @@ -FRAME_CLASS 1 FRAME_TYPE 1 - diff --git a/Tools/autotest/default_params/glider.parm b/Tools/autotest/default_params/glider.parm new file mode 100644 index 0000000000000..e0bc1102fbd9d --- /dev/null +++ b/Tools/autotest/default_params/glider.parm @@ -0,0 +1,49 @@ +LIM_PITCH_MAX 1000 +LIM_PITCH_MIN -1500 +LIM_ROLL_CD 3000 + +THR_MAX 0 +THR_FAILSAFE 2 +STALL_PREVENTION 0 +RTL_RADIUS 175 +WP_RADIUS 90 +KFF_RDDRMIX 0.07 + +RLL_RATE_FF 0.6 +RLL_RATE_P 0.5 +RLL_RATE_I 0.14 +RLL_RATE_D 0.01 +RLL_RATE_IMAX 0.67 +RLL2SRV_TCONST 0.7 +RLL2SRV_RMAX 30 + +PTCH_RATE_FF 0.5 +PTCH_RATE_P 0.3 +PTCH_RATE_I 0.9 +PTCH_RATE_D 0.01 +PTCH_RATE_IMAX 0.67 +PTCH2SRV_TCONST 0.45 +PTCH2SRV_RMAX_UP 75 +PTCH2SRV_RMAX_DN 75 + + +ARSPD_FBW_MIN 17 +ARSPD_FBW_MAX 45 + +HOME_RESET_ALT -1 + +TECS_INTEG_GAIN 0.25 +TECS_SPDWEIGHT 2 +TECS_PTCH_DAMP 0.6 +TECS_SINK_MAX 8.5 +TECS_PITCH_MAX 10 +TECS_PITCH_MIN -15 +TECS_OPTIONS 3 +TECS_PTCH_FF_V0 25 +TECS_HDEM_TCONST 2 + +NAVL1_PERIOD 20 +NAVL1_LIM_BANK 30 + +SCHED_LOOP_RATE 200 + diff --git a/Tools/autotest/default_params/stratoblimp.parm b/Tools/autotest/default_params/stratoblimp.parm new file mode 100644 index 0000000000000..a055cddb0aa33 --- /dev/null +++ b/Tools/autotest/default_params/stratoblimp.parm @@ -0,0 +1,46 @@ +# parameters for default StratoBlimp +SERVO1_FUNCTION 19 +SERVO2_FUNCTION 19 + +SERVO3_FUNCTION 73 +SERVO3_MIN 1000 +SERVO3_MAX 2000 + +SERVO4_FUNCTION 74 +SERVO4_MIN 1000 +SERVO4_MAX 2000 + +# no need for high loop rate +SIM_RATE_HZ 100 + +# avoid IMU cal +INS_ACCOFFS_X 0.001 +INS_ACCOFFS_Y 0.001 +INS_ACCOFFS_Z 0.001 +INS_ACCSCAL_X 1.001 +INS_ACCSCAL_Y 1.001 +INS_ACCSCAL_Z 1.001 +INS_ACC2OFFS_X 0.001 +INS_ACC2OFFS_Y 0.001 +INS_ACC2OFFS_Z 0.001 +INS_ACC2SCAL_X 1.001 +INS_ACC2SCAL_Y 1.001 +INS_ACC2SCAL_Z 1.001 +INS_ACC3OFFS_X 0.000 +INS_ACC3OFFS_Y 0.000 +INS_ACC3OFFS_Z 0.000 +INS_ACC3SCAL_X 1.000 +INS_ACC3SCAL_Y 1.000 +INS_ACC3SCAL_Z 1.000 + +# crude rudder control +RUDD_DT_GAIN 100 +NAVL1_PERIOD 35 + +RLL_RATE_I 0 +RLL_RATE_D 0 +RLL_RATE_FF 0.03 +ROLL_LIMIT_DEG 5 +PTCH_LIMIT_MAX_DEG 5 +PTCH_LIMIT_MIN_DEG -5 + diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 0da15f1c91e4f..0f02f32242fbe 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -91,7 +91,6 @@ def RotorRunup(self): raise NotAchievedException("Takeoff initiated before runup time complete %u" % runup_time) self.progress("Runup time %u" % runup_time) self.zero_throttle() - self.set_rc(8, 1000) self.land_and_disarm() self.mav.wait_heartbeat() @@ -199,25 +198,25 @@ def FlyEachFrame(self): if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( - ["--defaults", ','.join(defaults), ], + [], + defaults_filepath=defaults, model=model, wipe=True, ) self.takeoff(10) self.do_RTL() - self.set_rc(8, 1000) def governortest(self): '''Test Heli Internal Throttle Curve and Governor''' self.customise_SITL_commandline( - ["--defaults", ','.join(self.model_defaults_filepath('heli-gas')), ], + [], + defaults_filepath=self.model_defaults_filepath('heli-gas'), model="heli-gas", wipe=True, ) self.set_parameter("H_RSC_MODE", 4) self.takeoff(10) self.do_RTL() - self.set_rc(8, 1000) def hover(self): self.progress("Setting hover collective") @@ -278,7 +277,6 @@ def PosHoldTakeOff(self): ex = e self.land_and_disarm() - self.set_rc(8, 1000) self.context_pop() @@ -316,7 +314,6 @@ def StabilizeTakeOff(self): ex = e self.land_and_disarm() - self.set_rc(8, 1000) self.context_pop() @@ -365,8 +362,12 @@ def AutoRotation(self, timeout=600): timeout=timeout) self.context_collect('STATUSTEXT') self.progress("Triggering autorotate by raising interlock") + self.set_rc(3, 1000) self.set_rc(8, 1000) + self.wait_statustext("SS Glide Phase", check_context=True) + + self.change_mode('STABILIZE') self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", check_context=True, regex=True) @@ -842,6 +843,127 @@ def PIDNotches(self): if ex is not None: raise ex + def AutoTune(self): + """Test autotune mode""" + # test roll and pitch FF tuning + self.set_parameters({ + "ATC_ANG_RLL_P": 4.5, + "ATC_RAT_RLL_P": 0, + "ATC_RAT_RLL_I": 0.1, + "ATC_RAT_RLL_D": 0, + "ATC_RAT_RLL_FF": 0.15, + "ATC_ANG_PIT_P": 4.5, + "ATC_RAT_PIT_P": 0, + "ATC_RAT_PIT_I": 0.1, + "ATC_RAT_PIT_D": 0, + "ATC_RAT_PIT_FF": 0.15, + "ATC_ANG_YAW_P": 4.5, + "ATC_RAT_YAW_P": 0.18, + "ATC_RAT_YAW_I": 0.024, + "ATC_RAT_YAW_D": 0.003, + "ATC_RAT_YAW_FF": 0.024, + "AUTOTUNE_AXES": 3, + "AUTOTUNE_SEQ": 1, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.land_and_disarm() + + # test pitch rate P and Rate D tuning + self.set_parameters({ + "AUTOTUNE_AXES": 2, + "AUTOTUNE_SEQ": 2, + "AUTOTUNE_GN_MAX": 2.0, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.land_and_disarm() + + # test Roll rate P and Rate D tuning + self.set_parameters({ + "AUTOTUNE_AXES": 1, + "AUTOTUNE_SEQ": 2, + "AUTOTUNE_GN_MAX": 1.8, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.land_and_disarm() + + # test Roll and pitch angle P tuning + self.set_parameters({ + "AUTOTUNE_AXES": 3, + "AUTOTUNE_SEQ": 4, + "AUTOTUNE_GN_MAX": 2.0, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.land_and_disarm() + + # test yaw FF, rate P and Rate D, and angle P tuning + self.set_parameters({ + "AUTOTUNE_AXES": 4, + "AUTOTUNE_SEQ": 7, + "AUTOTUNE_GN_MAX": 2.0, + }) + + # Conduct testing from althold + self.takeoff(10, mode="ALT_HOLD") + + # hold position in loiter + self.change_mode('AUTOTUNE') + + tstart = self.get_sim_time() + self.wait_statustext('AutoTune: Success', timeout=1000) + now = self.get_sim_time() + self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.land_and_disarm() + + def land_and_disarm(self, **kwargs): + super(AutoTestHelicopter, self).land_and_disarm(**kwargs) + self.progress("Killing rotor speed") + self.set_rc(8, 1000) + + def do_RTL(self, **kwargs): + super(AutoTestHelicopter, self).do_RTL(**kwargs) + self.progress("Killing rotor speed") + self.set_rc(8, 1000) + def tests(self): '''return list of all tests''' ret = vehicle_test_suite.TestSuite.tests(self) @@ -859,6 +981,7 @@ def tests(self): self.TurbineStart, self.NastyMission, self.PIDNotches, + self.AutoTune, ]) return ret diff --git a/Tools/autotest/models/freestyle.json b/Tools/autotest/models/freestyle.json new file mode 100644 index 0000000000000..b0556fbedb18c --- /dev/null +++ b/Tools/autotest/models/freestyle.json @@ -0,0 +1,62 @@ +# 5 inch FPV Freestyle/Racing model + +{ + # total vehicle mass in kg + "mass" : 0.8, + + # vehicle diameter + "diagonal_size" : 0.25, + + # the ref parameters should be taken from a test + # with the copter flying at constant speed in zero wind. This is used + # to estimate the drag coefficient + "refSpd" : 20.0, # m/s + "refAngle" : 45.0, # degrees + "refVoltage" : 23.2, # volts + "refCurrent" : 5, # Amps + "refAlt" : 607, # meters AMSL + "refTempC" : 25, # degrees C + "refBatRes" : 0.0226, # BAT.Res from log + + # full battery voltage + "maxVoltage" : 25.2, + + # full battery capacity, Ah + # 0 means unlimited + "battCapacityAh" : 0, + + # MOT_THST_EXPO + "propExpo" : 0.7, + + # approximate maximum yaw rate in deg/sec + "refRotRate" : 700, + + # hover throttle from 0 to 1 + "hoverThrOut" : 0.125, + + # MOT_PWM_MIN + "pwmMin" : 1000, + + # MOT_PWM_MAX + "pwmMax" : 2000, + + # MOT_SPIN_MIN + "spin_min" : 0.01, + + # MOT_SPIN_MAX + "spin_max" : 0.95, + + # maximum motor slew rate, or zero to disable + "slew_max" : 0, + + # total effective disc area in sq m for 4 x 5 inch diameter rotors + "disc_area" : 0.204, + + # momentum drag coefficient + # ratio of momentum drag relative to a ducted rotor of the same effective disc area + "mdrag_coef" : 0.10, + + # number of motors + "num_motors" : 4 +} + diff --git a/Tools/autotest/models/freestyle.param b/Tools/autotest/models/freestyle.param new file mode 100644 index 0000000000000..6ab0ddad76446 --- /dev/null +++ b/Tools/autotest/models/freestyle.param @@ -0,0 +1,91 @@ +ACRO_OPTIONS 1.000000 +ACRO_RP_EXPO 0.400000 +ACRO_RP_RATE 533.000000 +ACRO_THR_MID 0.300000 +ACRO_TRAINER 0.000000 +ACRO_Y_EXPO 0.400000 +ACRO_Y_RATE 533.000000 +ANGLE_MAX 7000.000000 +ARMING_RUDDER 0.000000 +ATC_ACCEL_P_MAX 160000.000000 +ATC_ACCEL_R_MAX 160000.000000 +ATC_ACCEL_Y_MAX 120000.000000 +ATC_ANG_PIT_P 15.000000 +ATC_ANG_RLL_P 15.000000 +ATC_ANG_YAW_P 10.000000 +ATC_INPUT_TC 0.040000 +ATC_RAT_PIT_P 0.040000 +ATC_RAT_PIT_I 0.040000 +ATC_RAT_PIT_D 0.001200 +ATC_RAT_PIT_FLTD 60.000000 +ATC_RAT_PIT_FLTE 40.000000 +ATC_RAT_PIT_FLTT 60.000000 +ATC_RAT_PIT_SMAX 50.000000 +ATC_RAT_RLL_P 0.048000 +ATC_RAT_RLL_I 0.048000 +ATC_RAT_RLL_D 0.000800 +ATC_RAT_RLL_FLTD 60.000000 +ATC_RAT_RLL_FLTT 60.000000 +ATC_RAT_RLL_SMAX 50.000000 +ATC_RAT_YAW_P 0.500000 +ATC_RAT_YAW_I 0.050000 +ATC_RAT_YAW_D 0.010000 +ATC_RAT_YAW_FLTD 60.000000 +ATC_RAT_YAW_FLTE 2.000000 +ATC_RAT_YAW_FLTT 60.000000 +ATC_RAT_YAW_SMAX 50.000000 +ATC_SLEW_YAW 24000.000000 +ATC_THR_MIX_MAN 4.000000 +AUTO_OPTIONS 3.000000 +BATT_CAPACITY 1300.000000 +BATT_OPTIONS 64.000000 +CIRCLE_RATE 200.000000 +DISARM_DELAY 0.000000 +EK3_GLITCH_RAD 0.000000 +FLTMODE_CH 0.000000 +FRAME_CLASS 1.000000 +GCS_PID_MASK 7.000000 +INS_ACCEL_FILTER 15.000000 +INS_FAST_SAMPLE 3.000000 +INS_GYRO_FILTER 120.000000 +INS_HNTC2_ATT 60.000000 +INS_HNTC2_BW 10.000000 +INS_HNTC2_ENABLE 1.000000 +INS_HNTC2_FREQ 90.000000 +INS_HNTC2_HMNCS 15.000000 +INS_HNTC2_MODE 3.000000 +INS_HNTC2_OPTS 22.000000 +INS_HNTC2_REF 1.000000 +LAND_ALT_LOW 700.000000 +LOG_BITMASK 196607.000000 +LOG_DARM_RATEMAX 1.000000 +LOIT_SPEED 4000.000000 +LOIT_ACC_MAX 1000.000000 +LOIT_BRK_ACCEL 500.000000 +LOIT_BRK_JERK 1000.000000 +LOIT_BRK_DELAY 0.250000 +MOT_BAT_VOLT_MAX 25.200000 +MOT_BAT_VOLT_MIN 19.800000 +MOT_SPIN_ARM 0.010000 +MOT_SPIN_MIN 0.010000 +MOT_SPOOL_TIME 0.250000 +MOT_THST_EXPO 0.700000 +MOT_THST_HOVER 0.125000 +PILOT_SPEED_DN 500.000000 +PILOT_SPEED_UP 500.000000 +PILOT_Y_RATE 250.000000 +PSC_ACCZ_FLTD 40.000000 +PSC_ACCZ_FLTT 40.000000 +PSC_ACCZ_P 0.200000 +PSC_JERK_XY 10.000000 +PSC_VELZ_P 3.000000 +RC7_OPTION 0.000000 +RTL_ALT 700.000000 +RTL_LOIT_TIME 2000.000000 +RTL_SPEED 900.000000 +WPNAV_ACCEL 1100.000000 +WPNAV_ACCEL_Z 300.000000 +WPNAV_JERK 6.000000 +WPNAV_SPEED 3000.000000 +WPNAV_SPEED_DN 500.000000 +WPNAV_SPEED_UP 500.000000 diff --git a/Tools/autotest/param_metadata/param.py b/Tools/autotest/param_metadata/param.py index 818a0f9b97f97..ec7bea2176da5 100644 --- a/Tools/autotest/param_metadata/param.py +++ b/Tools/autotest/param_metadata/param.py @@ -127,10 +127,12 @@ def has_param(self, pname): 'gravities': 'standard acceleration due to gravity' , # g_n would be a more correct unit, but IMHO no one understands what g_n means 'octal' : 'octal' , 'RPM' : 'Revolutions Per Minute', + 'kg' : 'kilograms', 'kg/m/m' : 'kilograms per square meter', # metre is the SI unit name, meter is the american spelling of it 'kg/m/m/m': 'kilograms per cubic meter', 'litres' : 'litres', 'Ohm' : 'Ohm', + 'N' : 'Newtons', } required_param_fields = [ diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index 00d8ed1ac8905..1830e8f82a48d 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -542,6 +542,9 @@ def start_SITL(binary, cmd.extend(customisations) + if "--defaults" in customisations: + raise ValueError("--defaults must be passed in via defaults_filepath keyword argument, not as part of customisation list") # noqa + pexpect_logfile_prefix = stdout_prefix if pexpect_logfile_prefix is None: pexpect_logfile_prefix = os.path.basename(binary) diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 198dda7461cae..3682dbb01ac11 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -45,6 +45,12 @@ def __init__(self): "default_params_filename": ["default_params/copter.parm", "default_params/copter-hexa.parm" ], }, + "hexax": { + "waf_target": "bin/arducopter", + "default_params_filename": ["default_params/copter.parm", + "default_params/copter-hexa.parm", + "default_params/copter-X.parm", ], + }, "hexa-cwx": { "waf_target": "bin/arducopter", "default_params_filename": [ @@ -182,14 +188,26 @@ def __init__(self): "Callisto": { "model": "octa-quad:@ROMFS/models/Callisto.json", "waf_target": "bin/arducopter", - "default_params_filename": ["default_params/copter.parm", - "models/Callisto.param"], + "default_params_filename": [ + "default_params/copter.parm", + "default_params/copter-octaquad.parm", + "models/Callisto.param", + ], }, "quad-can": { "waf_target": "bin/arducopter", "default_params_filename": ["default_params/copter.parm", "default_params/quad-can.parm"], "periph_params_filename": ["default_params/periph.parm", "default_params/quad-periph.parm"], }, + "freestyle": { + "model": "X:@ROMFS/models/freestyle.json", + "waf_target": "bin/arducopter", + "default_params_filename": [ + "default_params/copter.parm", + "default_params/copter-X.parm", + "models/freestyle.param", + ], + }, }, }, "Helicopter": { @@ -305,6 +323,10 @@ def __init__(self): "waf_target": "bin/arduplane", "default_params_filename": [], # defaults are loaded in SIM_Plane.cpp }, + "glider": { + "waf_target": "bin/arduplane", + "default_params_filename": "default_params/glider.parm", + }, "quadplane-copter_tailsitter": { "waf_target": "bin/arduplane", "default_params_filename": ["default_params/quadplane.parm","default_params/quadplane-copter_tailsitter.parm"], @@ -350,6 +372,10 @@ def __init__(self): "extra_mavlink_cmds": "module load sitl_calibration;", "external": True, # lies! OTOH, hard to take off with this }, + "stratoblimp": { + "waf_target": "bin/arduplane", + "default_params_filename": "default_params/stratoblimp.parm", + }, }, }, "Rover": { diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 8cd4bc80826a2..98628a45d71b6 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -808,7 +808,6 @@ def CPUFailsafe(self): def QAssist(self): '''QuadPlane Assist tests''' - # find a motor peak self.takeoff(10, mode="QHOVER") self.set_rc(3, 1800) self.change_mode("FBWA") @@ -841,6 +840,7 @@ def QAssist(self): comparator=operator.eq) self.set_rc(3, 1300) + # Test angle assist self.context_push() self.progress("Rolling over to %.0f degrees" % -lim_roll_deg) self.set_rc(1, 1000) @@ -856,9 +856,31 @@ def QAssist(self): self.wait_roll(lim_roll_deg, 5) self.context_pop() self.set_rc(1, 1500) - self.set_parameter("Q_RTL_MODE", 1) - self.change_mode("RTL") - self.wait_disarmed(timeout=300) + + # Test alt assist, climb to 60m and set assist alt to 50m + self.context_push() + guided_loc = self.home_relative_loc_ne(0, 0) + guided_loc.alt = 60 + self.change_mode("GUIDED") + self.do_reposition(guided_loc) + self.wait_altitude(58, 62, relative=True) + self.set_parameter("Q_ASSIST_ALT", 50) + + # Try and descent to 40m + guided_loc.alt = 40 + self.do_reposition(guided_loc) + + # Expect alt assist to kick in, eg "Alt assist 48.9m" + self.wait_statustext(r"Alt assist \d*.\d*m", regex=True, timeout=100) + + # Test transition timeout, should switch to QRTL + self.set_parameter("Q_TRANS_FAIL_ACT", 1) + self.set_parameter("Q_TRANS_FAIL", 10) + self.wait_mode("QRTL") + + self.context_pop() + + self.wait_disarmed(timeout=200) def LoiterAltQLand(self): '''test loitering and qland with terrain involved''' diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index b08e1ebed3003..8df5e424c2be6 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -525,6 +525,27 @@ def DriveRTL(self, timeout=120): self.disarm_vehicle() self.progress("RTL Mission OK (%fm)" % home_distance) + def RTL_SPEED(self, timeout=120): + '''Test RTL_SPEED is honoured''' + + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 0, 0), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1000, 0, 0), + ]) + + self.wait_ready_to_arm() + self.arm_vehicle() + + self.change_mode('AUTO') + self.wait_current_waypoint(2, timeout=120) + for speed in 1, 5.5, 1.5, 7.5: + self.set_parameter("RTL_SPEED", speed) + self.change_mode('RTL') + self.wait_groundspeed(speed-0.1, speed+0.1, minimum_duration=10) + self.change_mode('HOLD') + self.do_RTL() + self.disarm_vehicle() + def AC_Avoidance(self): '''Test AC Avoidance switch''' self.context_push() @@ -2587,7 +2608,7 @@ def assert_receive_mission_ack(self, mission_type, raise NotAchievedException("Unexpected mission type %u want=%u" % (m.mission_type, mission_type)) if m.type != want_type: - raise NotAchievedException("Expected ack type got %u got %u" % + raise NotAchievedException("Expected ack type %u got %u" % (want_type, m.type)) def assert_filepath_content(self, filepath, want): @@ -6728,6 +6749,68 @@ def NetworkingWebServerPPP(self): shutil.copy('build/sitl/bin/ardurover.noppp', 'build/sitl/bin/ardurover') self.reboot_sitl() + def FenceFullAndPartialTransfer(self, target_system=1, target_component=1): + '''ensure starting a fence transfer then a partial transfer behaves + appropriately''' + # start uploading a 10 item list: + self.mav.mav.mission_count_send( + target_system, + target_component, + 10, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0) + # change our mind and try a partial mission upload: + self.mav.mav.mission_write_partial_list_send( + target_system, + target_component, + 3, + 3, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE) + # should get denied for that one: + self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_DENIED, + ) + # now wait for the original upload to be "cancelled" + self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED, + ) + + def MissionRetransfer(self, target_system=1, target_component=1): + '''torture-test with MISSION_COUNT''' +# self.send_debug_trap() + self.mav.mav.mission_count_send( + target_system, + target_component, + 10, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0) + self.context_push() + self.context_collect('STATUSTEXT') + self.mav.mav.mission_count_send( + target_system, + target_component, + 10000, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.wait_statustext('Only [0-9]+ items are supported', regex=True, check_context=True) + self.context_pop() + self.assert_not_receive_message('MISSION_REQUEST') + self.mav.mav.mission_count_send( + target_system, + target_component, + 10, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.assert_receive_mission_item_request(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, 0) + self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_OPERATION_CANCELLED, + ) + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6814,6 +6897,9 @@ def tests(self): self.MAV_CMD_BATTERY_RESET, self.NetworkingWebServer, self.NetworkingWebServerPPP, + self.RTL_SPEED, + self.MissionRetransfer, + self.FenceFullAndPartialTransfer, ]) return ret diff --git a/Tools/autotest/test_build_options.py b/Tools/autotest/test_build_options.py index 9d4b3f1dd411c..305ec8e30403b 100755 --- a/Tools/autotest/test_build_options.py +++ b/Tools/autotest/test_build_options.py @@ -147,7 +147,7 @@ def get_disable_defines(self, feature, options): if f.define not in ret: continue - print("%s requires %s" % (option.define, f.define), file=sys.stderr) + # print("%s requires %s" % (option.define, f.define), file=sys.stderr) added_one = True ret[option.define] = 0 break diff --git a/Tools/autotest/test_param_upgrade.py b/Tools/autotest/test_param_upgrade.py index 4728e84856a92..de389834432f8 100755 --- a/Tools/autotest/test_param_upgrade.py +++ b/Tools/autotest/test_param_upgrade.py @@ -14,6 +14,7 @@ import argparse import subprocess import time +import shutil import string import pathlib @@ -50,10 +51,18 @@ def vehicleinfo_key(self): return "ArduCopter" raise ValueError("Can't determine vehicleinfo_key from binary path") + def model(self): + path = self.binary.lower() + if "plane" in path: + return "quadplane" + if "copter" in path: + return "X" + raise ValueError("Can't determine vehicleinfo_key from binary path") + def run(self): self.start_SITL( binary=self.binary, - model="novehicle", + model=self.model(), wipe=True, sitl_home="1,1,1,1", ) @@ -90,10 +99,18 @@ def vehicleinfo_key(self): return "ArduCopter" raise ValueError("Can't determine vehicleinfo_key from binary path") + def model(self): + path = self.binary.lower() + if "plane" in path: + return "quadplane" + if "copter" in path: + return "X" + raise ValueError("Can't determine vehicleinfo_key from binary path") + def run(self): self.start_SITL( binary=self.binary, - model="novehicle", + model=self.model(), sitl_home="1,1,1,1", wipe=False, ) @@ -243,6 +260,7 @@ def run(self): self.run_git(["checkout", master_commit], show_output=False) self.run_git(["submodule", "update", "--recursive"], show_output=False) + shutil.rmtree("build", ignore_errors=True) board = "sitl" if "AP_Periph" in self.vehicle: board = "sitl_periph_universal" @@ -257,6 +275,7 @@ def run(self): self.run_git(["checkout", branch], show_output=False) self.run_git(["submodule", "update", "--recursive"], show_output=False) + shutil.rmtree("build", ignore_errors=True) util.build_SITL( self.build_target_name(self.vehicle), board=board, @@ -281,12 +300,14 @@ def __init__(self, vehicles=None, run_eedump_before=False, run_eedump_after=False, + master_branch="master", ): self.vehicles = vehicles self.param_changes = param_changes self.vehicles = vehicles self.run_eedump_before = run_eedump_before self.run_eedump_after = run_eedump_after + self.master_branch = master_branch if self.vehicles is None: self.vehicles = self.all_vehicles() @@ -310,6 +331,7 @@ def run(self): self.param_changes, run_eedump_before=self.run_eedump_before, run_eedump_after=self.run_eedump_after, + master_branch=self.master_branch, ) s.run() @@ -346,7 +368,12 @@ def run(self): default=False, help="run the (already-compiled) eedump tool on eeprom.bin after doing conversion", ) - + parser.add_argument( + "--master-branch", + type=str, + default="master", + help="master branch to use", + ) args = parser.parse_args() param_changes = [] @@ -374,5 +401,6 @@ def run(self): vehicles=vehicles, run_eedump_before=args.run_eedump_before, run_eedump_after=args.run_eedump_after, + master_branch=args.master_branch, ) x.run() diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 2b9755f25a215..ebc16cf3b2f53 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -465,6 +465,47 @@ def progress_text(self, current_value): return (f"Want=({self.target.lat},{self.target.lng}) distance={self.horizontal_error(current_value)}") +class WaitAndMaintainEKFFlags(WaitAndMaintain): + '''Waits for EKF status flags to include required_flags and have + error_bits *not* set.''' + def __init__(self, test_suite, required_flags, error_bits, **kwargs): + super(WaitAndMaintainEKFFlags, self).__init__(test_suite, **kwargs) + self.required_flags = required_flags + self.error_bits = error_bits + self.last_EKF_STATUS_REPORT = None + + def announce_start_text(self): + return f"Waiting for EKF value {self.required_flags}" + + def get_current_value(self): + self.last_EKF_STATUS_REPORT = self.test_suite.assert_receive_message('EKF_STATUS_REPORT', timeout=10) + return self.last_EKF_STATUS_REPORT.flags + + def validate_value(self, value): + if value & self.error_bits: + return False + + if (value & self.required_flags) != self.required_flags: + return False + + return True + + def success_text(self): + return "EKF Flags OK" + + def timeoutexception(self): + self.progress("Last EKF status report:") + self.progress(self.test_suite.dump_message_verbose(self.last_EKF_STATUS_REPORT)) + + return AutoTestTimeoutException(f"Failed to get EKF.flags={self.required_flags}") + + def progress_text(self, current_value): + error_bits_str = "" + if current_value & self.error_bits: + error_bits_str = " (error bits present)" + return (f"Want=({self.required_flags}) got={current_value}{error_bits_str}") + + class WaitAndMaintainArmed(WaitAndMaintain): def get_current_value(self): return self.test_suite.armed() @@ -2331,7 +2372,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_BARO_COUNT", "SIM_BARO_DELAY", "SIM_BARO_DISABLE", - "SIM_BARO_DRIFT", "SIM_BARO_FREEZE", "SIM_BARO_WCF_BAK", "SIM_BARO_WCF_DN", @@ -2531,7 +2571,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_RC_CHANCOUNT", "SIM_RICH_CTRL", "SIM_RICH_ENABLE", - "SIM_SERVO_SPEED", "SIM_SHIP_DSIZE", "SIM_SHIP_ENABLE", "SIM_SHIP_OFS_X", @@ -6045,13 +6084,14 @@ def context_stop_collecting(self, msg_type): del context.collections[msg_type] return ret - def context_pop(self, process_interaction_allowed=True): + def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False): """Set parameters to origin values in reverse order.""" dead = self.contexts.pop() # remove hooks first; these hooks can raise exceptions which # we really don't want... - for hook in dead.message_hooks: - self.remove_message_hook(hook) + if not hooks_already_removed: + for hook in dead.message_hooks: + self.remove_message_hook(hook) for script in dead.installed_scripts: self.remove_installed_script(script) for (message_id, interval_us) in dead.overridden_message_rates.items(): @@ -7995,8 +8035,10 @@ def wait_heartbeat(self, drain_mav=True, quiet=False, *args, **x): if m.get_srcSystem() == self.sysid_thismav(): return m - def wait_ekf_happy(self, timeout=45, require_absolute=True): + def wait_ekf_happy(self, require_absolute=True, **kwargs): """Wait for EKF to be happy""" + if "timeout" not in kwargs: + kwargs["timeout"] = 45 """ if using SITL estimates directly """ if (int(self.get_parameter('AHRS_EKF_TYPE')) == 10): @@ -8016,35 +8058,10 @@ def wait_ekf_happy(self, timeout=45, require_absolute=True): mavutil.mavlink.ESTIMATOR_POS_VERT_ABS | mavutil.mavlink.ESTIMATOR_PRED_POS_HORIZ_ABS) error_bits |= mavutil.mavlink.ESTIMATOR_GPS_GLITCH - self.wait_ekf_flags(required_value, error_bits, timeout=timeout) + WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run() - def wait_ekf_flags(self, required_value, error_bits, timeout=30): - self.progress("Waiting for EKF value %u" % required_value) - last_print_time = 0 - tstart = self.get_sim_time() - m = None - while timeout is None or self.get_sim_time_cached() < tstart + timeout: - m = self.mav.recv_match(type='EKF_STATUS_REPORT', blocking=True, timeout=timeout) - if m is None: - continue - current = m.flags - errors = current & error_bits - everything_ok = (errors == 0 and - current & required_value == required_value) - if everything_ok or self.get_sim_time_cached() - last_print_time > 1: - self.progress("Wait EKF.flags: required:%u current:%u errors=%u" % - (required_value, current, errors)) - last_print_time = self.get_sim_time_cached() - if everything_ok: - self.progress("EKF Flags OK") - return True - m_str = str(m) - if m is not None: - m_str = self.dump_message_verbose(m) - self.progress("Last EKF_STATUS_REPORT message:") - self.progress(m_str) - raise AutoTestTimeoutException("Failed to get EKF.flags=%u" % - required_value) + def wait_ekf_flags(self, required_value, error_bits, **kwargs): + WaitAndMaintainEKFFlags(self, required_value, error_bits, **kwargs).run() def wait_gps_disable(self, position_horizontal=True, position_vertical=False, timeout=30): """Disable GPS and wait for EKF to report the end of assistance from GPS.""" @@ -8409,7 +8426,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout) - start_message_hooks = self.mav.message_hooks + start_message_hooks = copy.copy(self.mav.message_hooks) prettyname = "%s (%s)" % (name, desc) self.start_test(prettyname) @@ -8421,6 +8438,8 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= orig_speedup = None + hooks_removed = False + ex = None try: self.check_rc_defaults() @@ -8444,6 +8463,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= for h in self.mav.message_hooks: if h not in start_message_hooks: self.mav.message_hooks.remove(h) + hooks_removed = True self.test_timings[desc] = time.time() - start_time reset_needed = self.contexts[-1].sitl_commandline_customised @@ -8470,7 +8490,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= reset_needed = True try: - self.context_pop(process_interaction_allowed=ardupilot_alive) + self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed) except Exception as e: self.print_exception_caught(e, send_statustext=False) passed = False @@ -8522,7 +8542,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= # pop off old contexts to clean up message hooks etc while len(self.contexts) > old_contexts_length: try: - self.context_pop(process_interaction_allowed=ardupilot_alive) + self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed) except Exception as e: self.print_exception_caught(e, send_statustext=False) self.progress("Done popping extra contexts") @@ -13682,7 +13702,7 @@ def GPSTypes(self): n = self.poll_home_position(timeout=120) distance = self.get_distance_int(orig, n) if distance > 1: - raise NotAchievedException("gps type %u misbehaving" % name) + raise NotAchievedException(f"gps type {name} misbehaving") def assert_gps_satellite_count(self, messagename, count): m = self.assert_receive_message(messagename) @@ -14205,6 +14225,8 @@ def add_fftd(self, fftd): sample_rate = 0 counts = 0 window = numpy.hanning(fft_len) + # The returned float array f contains the frequency bin centers in cycles per unit of the + # sample spacing (with zero at the start). freqmap = numpy.fft.rfftfreq(fft_len, 1.0 / messages[0].sample_rate_hz) # calculate NEBW constant 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/JHEM_JHEF405_bl.bin b/Tools/bootloaders/JHEM_JHEF405_bl.bin index 89ad64881e833..66453f2c23beb 100755 Binary files a/Tools/bootloaders/JHEM_JHEF405_bl.bin and b/Tools/bootloaders/JHEM_JHEF405_bl.bin differ diff --git a/Tools/bootloaders/JHEM_JHEF405_bl.hex b/Tools/bootloaders/JHEM_JHEF405_bl.hex index c5856052cd411..aaeafa088a23c 100644 --- a/Tools/bootloaders/JHEM_JHEF405_bl.hex +++ b/Tools/bootloaders/JHEM_JHEF405_bl.hex @@ -1,26 +1,26 @@ :020000040800F2 :1000000000060020E1010008E3010008E301000808 :10001000E3010008E3010008E3010008E301000830 -:10002000E3010008E3010008E30100086D2F000868 +:10002000E3010008E3010008E3010008AD35000822 :10003000E3010008E3010008E3010008E301000810 :10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E3010008153200083D32000802 -:10006000653200088D320008B5320008E30100084F +:10005000E3010008E3010008553800087D38000876 +:10006000A5380008CD380008F5380008E30100087D :10007000E3010008E3010008E3010008E3010008D0 :10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008DD32000885 +:10009000E3010008E3010008E30100081D3900083E :1000A000E3010008E3010008E3010008E3010008A0 -:1000B000B1330008E3010008E3010008E301000890 +:1000B000053A0008E3010008E3010008E301000835 :1000C000E3010008E3010008E3010008E301000880 :1000D000E3010008E3010008E3010008E301000870 -:1000E00041330008E3010008E3010008E3010008D0 +:1000E00081390008E3010008E3010008E30100088A :1000F000E3010008E3010008E3010008E301000850 :10010000E3010008E3010008E3010008E30100083F :10011000E3010008E3010008E3010008E30100082F :10012000E3010008E3010008E3010008E30100081F :10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008212700089B -:10015000E3010008E3010008E3010008E3010008EF +:10014000E3010008E3010008E3010008612D000855 +:10015000E3010008E3010008E3010008F1390008A9 :10016000E3010008E3010008E3010008E3010008DF :10017000E3010008E3010008E3010008E3010008CF :10018000E3010008E3010008E3010008E3010008BF @@ -35,43 +35,43 @@ :100210004F8FBFF36F8F40F20000C0F2F0004EF638 :100220008851CEF200010860BFF34F8FBFF36F8F8C :100230004FF00000E1EE100A4EF63C71CEF20001E4 -:100240000860062080F31488BFF36F8F01F030FF41 -:1002500002F02AFE4FF055301F491B4A91423CBF25 +:100240000860062080F31488BFF36F8F02F050FA25 +:1002500003F04AF94FF055301F491B4A91423CBF09 :1002600041F8040BFAE71D49184A91423CBF41F896 :10027000040BFAE71A491B4A1B4B9A423EBF51F83E :10028000040B42F8040BF8E700201849184A914281 -:100290003CBF41F8040BFAE701F00EFF02F058FEF4 +:100290003CBF41F8040BFAE702F02EFA03F078F9BC :1002A000144C154DAC4203DA54F8041B8847F9E7A7 :1002B00000F042F8114C124DAC4203DA54F8041B22 -:1002C0008847F9E701F0F6BE000600200022002072 +:1002C0008847F9E702F016BA000600200022002055 :1002D0000000000808ED00E00000002000060020FB -:1002E0007837000800220020402200204022002011 -:1002F000602E0020E0010008E0010008E001000895 +:1002E000103E0008002200204C2200205022002056 +:1002F000F0300020E0010008E0010008E001000803 :10030000E00100082DE9F04F2DED108AC1F80CD066 :10031000C3689D46BDEC108ABDE8F08F002383F3CF -:1003200011882846A047002001F072FAFEE701F08C -:1003300001FA00DFFEE7000038B500F0BBFB01F07A -:1003400087FE054601F0AAFE0446C8B90E4B9D4241 +:1003200011882846A047002001F092FDFEE701F069 +:1003300021FD00DFFEE7000038B500F0D1FB02F040 +:10034000A7F9054602F0CAF90446C8B90E4B9D420A :1003500018D001339D4218BF044641F2883504BFCE -:1003600001240025002001F07DFE0CB100F074F89E -:1003700000F000FD284600F0BFF800F06DF8F9E746 +:1003600001240025002002F09DF90CB100F074F882 +:1003700000F016FD284600F0BFF800F06DF8F9E730 :100380000025EFE70546EDE7010007B008B500F0EE -:1003900063FBA0F120035842584108BD07B541F264 -:1003A0001203022101A8ADF8043000F073FB03B082 +:1003900073FBA0F120035842584108BD07B541F254 +:1003A0001203022101A8ADF8043000F083FB03B072 :1003B0005DF804FB38B5302383F3118817480368D0 -:1003C0000BB101F0F1FA164A144800234FF47A7188 -:1003D00001F0E0FA002383F31188124C236813B173 +:1003C0000BB101F011FE164A144800234FF47A7164 +:1003D00001F000FE002383F31188124C236813B14F :1003E0002368013B2360636813B16368013B63606A -:1003F0000D4D2B7833B963687BB9022000F024FCE3 +:1003F0000D4D2B7833B963687BB9022000F03AFCCD :10040000322363602B78032B07D163682BB902205A -:1004100000F01AFC4FF47A73636038BD402200206C -:10042000B50300086023002058220020084B1870F4 +:1004100000F030FC4FF47A73636038BD5022002046 +:10042000B50300087023002068220020084B1870D4 :1004300003280CD8DFE800F008050208022000F0CD -:10044000F9BB022000F0ECBB024B00225A6070475F -:100450005822002060230020234B244A10B51C465C +:100440000FBC022000F002BC024B00225A60704731 +:100450006822002070230020234B244A10B51C463C :10046000196801313FD004339342F9D16268A24246 :1004700039D31F4B9B6803F1006303F540439A4255 -:1004800031D2002000F030FB0220FFF7CFFF194BE4 +:1004800031D2002000F046FB0220FFF7CFFF194BCE :100490001A6C00221A64196E1A66196E596C5A6425 :1004A000596E5A665A6E5A6942F080025A615A6908 :1004B00022F080025A615A691A6942F000521A61A8 @@ -79,15 +79,15 @@ :1004D0003021C3F8084DD4E9003281F311889D46DC :1004E00083F30888104710BD00C0000820C0000832 :1004F00000220020003802402DE9F04F93B0AA4BB3 -:1005000000902022FF210AA89D6800F0DDFBA74A89 +:1005000000902022FF210AA89D6800F0F3FBA74A73 :100510001378A3B9A648012103601170302383F337 -:10052000118803680BB101F03FFAA24AA0480023EA -:100530004FF47A7101F02EFA002383F31188009BA7 +:10052000118803680BB101F05FFDA24AA0480023C7 +:100530004FF47A7101F04EFD002383F31188009B84 :1005400013B19D4B009A1A609C4A009C1378032BB0 :100550001EBF00231370984A4FF0000A18BF536063 -:10056000D3465646D146012000F064FB24B1924B9D -:100570001B68002B00F01182002000F06DFA039040 -:10058000039B002BF2DB012000F04AFB039B213B85 +:10056000D3465646D146012000F07AFB24B1924B87 +:100570001B68002B00F01182002000F07DFA039030 +:10058000039B002BF2DB012000F060FB039B213B6F :10059000162BE8D801A252F823F000BFF905000895 :1005A00021060008B5060008670500086705000871 :1005B000670500083F0700080F0900082908000820 @@ -96,799 +96,905 @@ :1005E00067050008A109000805060008990600082B :1005F000670500088B0800080220FFF7C7FE0028E7 :1006000040F0F581009B0221BAF1000F08BF1C46A3 -:1006100005A841F21233ADF8143000F03BFAA2E71E -:100620004FF47A7000F018FA071EEBDB0220FFF798 +:1006100005A841F21233ADF8143000F04BFAA2E70E +:100620004FF47A7000F028FA071EEBDB0220FFF788 :10063000ADFE0028E6D0013F052F00F2DA81DFE8A9 :1006400007F0030A0D10133605230593042105A8AE -:1006500000F020FA17E054480421F9E75848042133 +:1006500000F030FA17E054480421F9E75848042123 :10066000F6E758480421F3E74FF01C08404600F035 -:100670003DFA08F104080590042105A800F00AFAE3 +:1006700053FA08F104080590042105A800F01AFABD :10068000B8F12C0FF2D1012000FA07F747EA0B0B63 -:100690005FFA8BFB4FF0000900F062FB26B10BF014 +:100690005FFA8BFB4FF0000900F078FB26B10BF0FE :1006A0000B030B2B08BF0024FFF778FE5BE74648DF :1006B0000421CDE7002EA5D00BF00B030B2BA1D10D :1006C0000220FFF763FE074600289BD0012000F0C0 -:1006D0000BFA0220FFF7AAFE00261FFA86F8404612 -:1006E00000F012FA044690B10021404600F01CFAD6 +:1006D00021FA0220FFF7AAFE00261FFA86F84046FC +:1006E00000F028FA044690B10021404600F032FAAA :1006F00001360028F1D1BA46044641F21213022114 -:1007000005A8ADF814303E4600F0C4F92BE70120EF +:1007000005A8ADF814303E4600F0D4F92BE70120DF :10071000FFF78CFE2546244B9B68AB4207D9284641 -:1007200000F0E4F9013040F067810435F3E7234B32 +:1007200000F0FAF9013040F067810435F3E7234B1C :1007300000251D70204BBA465D603E46ACE7002E9A :100740003FF460AF0BF00B030B2B7FF45BAF022089 -:10075000FFF76CFE322000F07FF9B0F10008FFF6E1 +:10075000FFF76CFE322000F08FF9B0F10008FFF6D1 :1007600051AF18F003077FF44DAF0F4A926808EBC2 :10077000050393423FF646AFB8F5807F3FF742AF9F -:10078000124B0193B84523DD4FF47A7000F064F901 +:10078000124B0193B84523DD4FF47A7000F074F9F1 :100790000390039A002AFFF635AF019B039A03F8F2 -:1007A000012B0137EDE700BF002200205C23002071 -:1007B00040220020B50300086023002058220020BA -:1007C00004220020082200200C2200205C220020AD +:1007A000012B0137EDE700BF002200206C23002061 +:1007B00050220020B503000870230020682200208A +:1007C00004220020082200200C2200206C2200209D :1007D000C820FFF7DBFD074600283FF413AF1F2DAD :1007E00011D8C5F1200242450AAB25F0030028BF0D -:1007F000424683490192184400F040FA019A804829 -:10080000FF2100F061FA4FEAA8037D490193C8F384 -:100810008702284600F060FA064600283FF46DAFD4 +:1007F000424683490192184400F056FA019A804813 +:10080000FF2100F077FA4FEAA8037D490193C8F36E +:100810008702284600F076FA064600283FF46DAFBE :10082000019B05EB830537E70220FFF7AFFD0028AA -:100830003FF4E8AE00F0A4F900283FF4E3AE00274F +:100830003FF4E8AE00F0BAF900283FF4E3AE002739 :10084000B846704B9B68BB4218D91F2F11D80A9B22 :1008500001330ED027F0030312AA134453F8203CAF -:1008600005934046042205A900F0AEFA04378046FD -:10087000E7E7384600F03AF90590F2E7CDF8148042 -:10088000042105A800F006F906E70023642104A866 -:10089000049300F0F5F800287FF4B4AE0220FFF7CF -:1008A00075FD00283FF4AEAE049800F051F90590B4 -:1008B000E6E70023642104A8049300F0E1F800288F +:1008600005934046042205A900F0FAFA04378046B1 +:10087000E7E7384600F050F90590F2E7CDF814802C +:10088000042105A800F016F906E70023642104A856 +:10089000049300F005F900287FF4B4AE0220FFF7BE +:1008A00075FD00283FF4AEAE049800F067F905909E +:1008B000E6E70023642104A8049300F0F1F800287F :1008C0007FF4A0AE0220FFF761FD00283FF49AAE4E -:1008D000049800F04DF9EAE70220FFF757FD0028E1 -:1008E0003FF490AE00F05CF9E1E70220FFF74EFD27 -:1008F00000283FF487AE05A9142000F057F9042121 -:100900000746049004A800F0C5F83946B9E732203C -:1009100000F0A2F8071EFFF675AEBB077FF472AEBB +:1008D000049800F063F9EAE70220FFF757FD0028CB +:1008E0003FF490AE00F072F9E1E70220FFF74EFD11 +:1008F00000283FF487AE05A9142000F06DF904210B +:100900000746049004A800F0D5F83946B9E732202C +:1009100000F0B2F8071EFFF675AEBB077FF472AEAB :10092000384A926807EB090393423FF66BAE022008 :10093000FFF72CFD00283FF465AE27F003074F4476 -:10094000B9453FF4A9AE484600F0D0F8042105901F -:1009500005A800F09FF809F10409F1E74FF47A7057 -:10096000FFF714FD00283FF44DAE00F009F9002810 +:10094000B9453FF4A9AE484600F0E6F80421059009 +:1009500005A800F0AFF809F10409F1E74FF47A7047 +:10096000FFF714FD00283FF44DAE00F01FF90028FA :1009700044D00A9B01330BD008220AA9002000F0C2 -:10098000ABF900283AD02022FF210AA800F09CF9F8 -:10099000FFF704FD1C4800F041FF13B0BDE8F08FE5 +:10098000C1F900283AD02022FF210AA800F0B2F9CC +:10099000FFF704FD1C4801F061FA13B0BDE8F08FC9 :1009A000002E3FF42FAE0BF00B030B2B7FF42AAE7F -:1009B0000023642105A8059300F062F8074600288B +:1009B0000023642105A8059300F072F8074600287B :1009C0007FF420AE0220FFF7E1FC804600283FF4D0 -:1009D00019AEFFF7E3FC41F2883000F01FFF0598E5 -:1009E00000F0F0F9464600F0BBF93C46BBE5064690 +:1009D00019AEFFF7E3FC41F2883001F03FFA0598C9 +:1009E00000F01CFA464600F0D1F93C46BBE506464D :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 -:100C2000022802BF024B4FF000729A61704700BF6A -:100C300000000240022802BF024B4FF400729A618A -:100C4000704700BF00000240022801BF024A5369FA -:100C500083F40073536170470000024070B504468E -: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 -:1035E0000403090425424F41524425004A48454DF1 -:1035F0005F4A484546343035003031323334353651 -:10360000373839414243444546000000004000003D -:1036100000400000004000000040000000000100E9 -:103620000000020000000200000002000000020092 -:103630000000020000000200000002000000000084 -:103640007112000829150008D51500084000400037 -:10365000C82D0020C82D002001000000D82D00201A -:103660008000000040010000030000006D61696EF1 -:103670000069646C650000000000842A00000000FE -:10368000AAAAAAAA00000024FFFD00000000000072 -:1036900000A00A004000001100000000AAAAAAAA87 -:1036A00040000011FFFF00000000000000000000CB -:1036B0000000000000000000AAAAAAAA0000000062 -:1036C000FFFF0000000000000000000000000000FC -:1036D00000000000AAAAAAAA00000000FFFF000044 -:1036E00000000000000000000000000000000000DA -:1036F000AAAAAAAA00000000FFFF00000000000024 -:10370000000000000000000000000000AAAAAAAA11 -:1037100000000000FFFF00000000000000000000AB -:103720000000000000000000AAAAAAAA00000000F1 -:10373000FFFF00000000000000000000000000008B -:10374000000000000A00000000000000030000006C -:103750000000000000000000000000000000000069 -:103760000000000000000000000000000000000059 -:10377000000000000000000039040000000000000C -:1037800000400F0000000000FF009600000000084D -:10379000009600000000080004000000E03500086A -:1037A0000000000000000000000000000000000019 -:0837B000000000000000000011 +:100A00006C22002000220020A08601002DE9F84F72 +:100A10004FF47A73DFF85880DFF8589006460D4699 +:100A200002FB03F7002498F900305A1C5FFA84FA9D +:100A300001D0A34212D159F8240003682A46D3F802 +:100A400020B031463B46D847854207D1074B0120AD +:100A500083F800A0BDE8F88F0124E4E7002CFBD068 +:100A60004FF4FA7001F0FAF90020F3E7B823002000 +:100A7000102200201422002007B500230246012185 +:100A80000DF107008DF80730FFF7C0FF20B19DF88A +:100A9000070003B05DF804FB4FF0FF30F9E70000FA +:100AA0000A4608B50421FFF7B1FF80F00100C0B28B +:100AB000404208BD30B4074B0A461978064B53F83C +:100AC00021402368DD69054B0146AC46204630BC19 +:100AD000604700BFB823002014220020A086010038 +:100AE00070B501F0DBFC094E094D30800024286808 +:100AF0003388834208D901F0CBFC2B6804440133CE +:100B0000B4F5404F2B60F2D370BD00BFBA23002074 +:100B10007823002001F070BD00F1006000F5404036 +:100B20000068704700F10060920000F5404001F05D +:100B3000FBBC0000054B1A68054B1B889B1A8342BF +:100B400002D9104401F0A4BC002070477823002093 +:100B5000BA23002038B5084D044629B1286820443E +:100B6000BDE8384001F0B4BC2868204401F098FC8E +:100B70000028F3D038BD00BF7823002010F0030315 +:100B80000AD1B0F5047F05D200F10050A0F5104065 +:100B9000D0F80038184670470023FBE700F10050FA +:100BA000A0F51040D0F8100A70470000064991F8EF +:100BB000243033B10023086A81F824300822FFF77B +:100BC000B1BF0120704700BF7C230020014B186893 +:100BD000704700BF002004E070B5194B1D68194B29 +:100BE0000138C5F30B0408442D0C04221E88A642CC +:100BF0000BD15C680A46013C824213460FD214F9BD +:100C0000016F4EB102F8016BF6E7013A03F10803F8 +:100C1000ECD181420B4602D22C2203F8012B0A4A66 +:100C200005241688AE4204D1984284BF967803F812 +:100C3000016B013C02F10402F3D1581A70BD00BFF0 +:100C4000002004E0F43A0008E03A0008022802BF5D +:100C5000024B4FF000729A61704700BF00000240E3 +:100C6000022802BF024B4FF400729A61704700BF26 +:100C700000000240022801BF024A536983F4007356 +:100C8000536170470000024070B504464FF47A7615 +:100C90004CB1412C254628BF412506FB05F001F04B +:100CA000DDF8641BF4E770BD10B50023934203D058 +:100CB000CC5CC4540133F9E710BD000010B5013815 +:100CC00010F9013F3BB191F900409C4203D11AB1A8 +:100CD0000131013AF4E71AB191F90020981A10BDD8 +:100CE0001046FCE703460246D01A12F9011B002900 +:100CF000FAD1704702440346934202D003F8011B25 +:100D0000FAE770472DE9F8431F4D144695F8242063 +:100D10000746884652BBDFF870909CB395F82430A4 +:100D20002BB92022FF2148462F62FFF7E3FF95F8F9 +:100D30002400C0F10802A24228BF2246D6B2414692 +:100D4000920005EB8000FFF7AFFF95F82430A41B5D +:100D50001E44F6B2082E17449044E4B285F824608D +:100D6000DBD1FFF723FF0028D7D108E02B6A03EB84 +:100D700082038342CFD0FFF719FF0028CBD1002098 +:100D8000BDE8F8830120FBE77C230020024B1A78A2 +:100D9000024B1A70704700BFB823002010220020B9 +:100DA00038B5194C194D204600F0BEFB29462046A7 +:100DB00000F0E6FB2D686A6DD2F8043843F00203B8 +:100DC000C2F804384FF47A70FFF75EFF10492846E6 +:100DD00000F0DCFC6A6D0F4DD2F8043828680E492B +:100DE00023F00203C2F80438A0424FF4E1330B6051 +:100DF00001D000F0F9FA6868A04204D0BDE838409C +:100E0000054900F0F1BA38BD98280020FC3B0008E5 +:100E1000043C000814220020A423002070B50C4BD1 +:100E20000C4D1E780C4B55F826209A4204460DD0E6 +:100E30000A4B002114221846FFF75CFF04600146AC +:100E400055F82600BDE8704000F0CEBA70BD00BF76 +:100E5000B82300201422002098280020A42300207A +:100E600030B5094D0A4491420DD011F8013B58406C +:100E7000082340F30004013B2C4013F0FF0384EAF5 +:100E80005000F6D1EFE730BD2083B8ED026843682B +:100E90001143016003B1184770470000024AD3684C +:100EA00043F0C003D36070470014014010B5084CF4 +:100EB000084A0021204600F075FA074BC4F85C325E +:100EC00003F1454303F52943C4F8603210BD00BF68 +:100ED000BC2300209D0E000800140140234A037C1F +:100EE000002918BF0A46012B30B5C0F868220CD182 +:100EF0001F4B984209D11F4B596C41F02001596496 +:100F0000596E41F0200159665B6EB2F904501468C5 +:100F1000D0F86032D0F85C12002D03EB5403B3FB21 +:100F2000F4F3BEBF23F0070503F0070343EA4503CC +:100F300094888B60D38843F040030B61138943F09E +:100F400001034B6144F4045343F02C03CB6004F4DD +:100F5000A05400230B60B4F5806F0B684B680CBF86 +:100F60007F23FF2380F8643230BD00BF143B0008AC +:100F7000BC230020003802402DE9F041D0F85C622B +:100F8000F7683368DA0504469DB20DD5302383F344 +:100F900011884FF480610430FFF778FF6FF480739D +:100FA0003360002383F31188302383F3118804F125 +:100FB000040815F02F033AD183F31188380615D5AC +:100FC000290613D5302383F3118804F1380000F08B +:100FD00065F900284EDA0821201DFFF757FF4FF66C +:100FE0007F733B40F360002383F311887A0616D5A4 +:100FF0006B0614D5302383F31188D4E913239A4266 +:101000000AD1236C43B127F040073F041021201D73 +:101010003F0CFFF73BFFF760002383F31188D4F800 +:101020006822D36843B3BDE8F041106918472B0725 +:1010300014D015F0080F0CBF00214FF48071E807A1 +:1010400048BF41F02001AA0748BF41F040016B07AB +:1010500048BF41F080014046FFF718FFAD067368B6 +:1010600005D594F864122046194000F0CBF9356894 +:10107000ADB29EE77060B6E7BDE8F081F8B5154601 +:1010800082680669AA420B46816938BF8568761A6C +:10109000B54204460BD218462A46FFF705FEA3695F +:1010A0002B44A361A3685B1BA3602846F8BD0CD941 +:1010B00018463246FFF7F8FDAF1BE1683A46304468 +:1010C000FFF7F2FDE3683B44EBE718462A46FFF7DB +:1010D000EBFDE368E5E7000083689342F7B515464A +:1010E000044638BF8568D0E90460361AB5420BD291 +:1010F0002A46FFF7D9FD63692B446361A36828463C +:101100005B1BA36003B0F0BD0DD932460191FFF720 +:10111000CBFD0199E068AF1B3A463144FFF7C4FDAF +:10112000E3683B44E9E72A46FFF7BEFDE368E4E7EE +:1011300010B50A440024C361029B8460C0E900002A +:10114000C0E90511C1600261036210BD08B5D0E9B4 +:101150000532934201D1826882B98268013282608D +:101160005A1C42611970D0E904329A4224BFC36804 +:101170004361002100F08EFE002008BD4FF0FF30DB +:10118000FBE7000070B5302304460E4683F3118858 +:10119000A568A5B1A368A269013BA360531CA36124 +:1011A00015782269934224BFE368A361E3690BB118 +:1011B00020469847002383F31188284607E03146EC +:1011C000204600F057FE0028E2DA85F3118870BD52 +:1011D0002DE9F74F04460E4617469846D0F81C9066 +:1011E0004FF0300A8AF311884FF0000B154665B1B5 +:1011F0002A4631462046FFF741FF034660B9414683 +:10120000204600F037FE0028F1D0002383F3118838 +:10121000781B03B0BDE8F08FB9F1000F03D0019047 +:101220002046C847019B8BF31188ED1A1E448AF3B0 +:101230001188DCE7C0E90511C160C3611144009B5E +:101240008260C0E90000016103627047F8B504469E +:101250000D461646302383F31188A768A7B1A3680B +:10126000013BA36063695A1C62611D70D4E90432BA +:101270009A4224BFE3686361E3690BB12046984753 +:10128000002080F3118807E03146204600F0F2FD8F +:101290000028E2DA87F31188F8BD0000D0E90523C1 +:1012A0009A4210B501D182687AB9826801328260AF +:1012B0005A1C82611C7803699A4224BFC368836107 +:1012C000002100F0E7FD204610BD4FF0FF30FBE7A6 +:1012D0002DE9F74F04460E4617469846D0F81C9065 +:1012E0004FF0300A8AF311884FF0000B154665B1B4 +:1012F0002A4631462046FFF7EFFE034660B94146D5 +:10130000204600F0B7FD0028F1D0002383F31188B8 +:10131000781B03B0BDE8F08FB9F1000F03D0019046 +:101320002046C847019B8BF31188ED1A1E448AF3AF +:101330001188DCE7026843681143016003B1184774 +:10134000704700001430FFF743BF00004FF0FF3339 +:101350001430FFF73DBF00003830FFF7B9BF000081 +:101360004FF0FF333830FFF7B3BF00001430FFF702 +:1013700009BF00004FF0FF311430FFF703BF00003A +:101380003830FFF763BF00004FF0FF323830FFF70F +:101390005DBF0000012914BF6FF0130000207047EB +:1013A000FFF784BD37B515460E4A02600022426041 +:1013B000C0E902220122044602740B46009000F1AB +:1013C0005C014FF480721430FFF7B2FE00942B469C +:1013D0004FF4807204F5AE7104F13800FFF72AFF74 +:1013E00003B030BD283B000810B53023044683F31A +:1013F0001188FFF773FD02232374002080F3118806 +:1014000010BD000038B5C36904460D461BB9042160 +:101410000844FFF78FFF294604F11400FFF796FEFA +:10142000002806DA201D4FF40061BDE83840FFF7C0 +:1014300081BF38BD026843681143016003B118479A +:101440007047000013B5446BD4F894341A681178CF +:10145000042915D1217C022912D11979128901237D +:101460008B4013420CD101A904F14C0001F0F8FEAD +:10147000D4F89444019B21790246206800F0D0F909 +:1014800002B010BD143001F07BBE00004FF0FF33FE +:10149000143001F075BE00004C3001F04DBF00006B +:1014A0004FF0FF334C3001F047BF0000143001F023 +:1014B00049BE00004FF0FF31143001F043BE000080 +:1014C0004C3001F019BF00004FF0FF324C3001F0FA +:1014D00013BF00000020704710B5D0F894341A688C +:1014E00011780429044617D1017C022914D15979B5 +:1014F000528901238B4013420ED1143001F0DCFDE0 +:10150000024648B1D4F894444FF48073617920685E +:10151000BDE8104000F072B910BD0000406BFFF74D +:10152000DBBF0000704700007FB5124B0360002353 +:101530004360C0E90233012502260F4B05740446BF +:101540000290019300F18402294600964FF48073C3 +:10155000143001F08DFD094B0294CDE9006304F5D0 +:1015600023724FF48073294604F14C0001F054FEBD +:1015700004B070BD503B00081D150008451400085C +:101580000B68302282F311880A7903EB82029061A2 +:101590004A79093243F822008A7912B103EB8203B7 +:1015A00098610223C0F894140374002080F311881A +:1015B0007047000038B5037F044613B190F85430EB +:1015C000ABB9201D01250221FFF734FF04F11400FF +:1015D00025776FF0010100F069FC84F8545004F1A4 +:1015E0004C006FF00101BDE8384000F05FBC38BD31 +:1015F00010B5012104460430FFF71CFF00232377B8 +:1016000084F8543010BD000038B50446002514306D +:1016100001F046FD04F14C00257701F015FE201D78 +:1016200084F854500121FFF705FF2046BDE83840FB +:10163000FFF752BF90F8443003F06003202B07D12E +:1016400090F84520212A4FF0000303D81F2A06D81E +:1016500000207047222AFBD1C0E90E3303E0034A81 +:1016600082630722C2630364012070471C220020AA +:1016700037B5D0F894341A681178042904461AD181 +:10168000017C022917D11979128901238B40134259 +:1016900011D100F14C05284601F096FE58B101A980 +:1016A000284601F0DDFDD4F89444019B21790246DF +:1016B000206800F0B5F803B030BD0000F0B500EBD5 +:1016C000810385B09E6904460D46FEB1302383F345 +:1016D000118804EB8507301D0821FFF7ABFEFB687E +:1016E0005B691B6806F14C001BB1019001F0C6FD5F +:1016F000019803A901F0B4FD024648B1039B2946B5 +:10170000204600F08DF8002383F3118805B0F0BD6A +:10171000FB685A691268002AF5D01B8A013B134006 +:10172000F1D104F14402EAE7093138B550F821401B +:10173000DCB1302383F31188D4F8942413685279F0 +:1017400003EB8203DB689B695D6845B10421601887 +:10175000FFF770FE294604F1140001F0B7FC2046A3 +:10176000FFF7BAFE002383F3118838BD70470000ED +:1017700001F016B8012303700023C0E90133C361EF +:1017800083620362C36243620363704738B50446F1 +:10179000302383F311880025C0E90355C0E90555BE +:1017A000416001F00DF80223237085F3118828466B +:1017B00038BD000070B500EB810305465069DA6062 +:1017C0000E46144618B110220021FFF793FAA069C3 +:1017D00018B110220021FFF78DFA31462846BDE8E6 +:1017E000704001F0B7B80000826802F00112826018 +:1017F0000022C0E90422826101F038B9F0B400EBA4 +:1018000081044789E4680125A4698D403D434581F1 +:1018100023600023A2606360F0BC01F053B90000B4 +:10182000F0B400EB81040789E468012564698D4008 +:101830003D43058123600023A2606360F0BC01F09A +:10184000CDB9000070B50223002504460370C0E93D +:101850000255C0E90455C564856180F8345001F033 +:1018600015F863681B6823B129462046BDE870401F +:10187000184770BD0378052B10B504460AD080F8D0 +:1018800050300523037043681B680BB1042198474F +:101890000023A36010BD00000178052906D190F84F +:1018A0005020436802701B6803B11847704700005E +:1018B00070B590F83430044613B1002380F834300A +:1018C00004F14402204601F0F3F863689B68B3B961 +:1018D00094F8443013F0600535D00021204601F023 +:1018E00093FB0021204601F085FB63681B6813B160 +:1018F000062120469847062384F8343070BD2046E0 +:1019000098470028E4D0B4F84A30E26B9A4288BF86 +:10191000E36394F94430E56B002B4FF0300380F221 +:101920000381002D00F0F280092284F8342083F333 +:1019300011880021D4E90E232046FFF771FF002310 +:1019400083F31188DAE794F8452003F07F0343EA34 +:10195000022340F20232934200F0C58021D8B3F551 +:10196000807F48D00DD8012B3FD0022B00F0938010 +:10197000002BB2D104F14C02A2630222E263236481 +:10198000C1E7B3F5817F00F09B80B3F5407FA4D120 +:1019900094F84630012BA0D1B4F84C3043F0020348 +:1019A00032E0B3F5006F4DD017D8B3F5A06F31D04A +:1019B000A3F5C063012B90D8636894F846205E6855 +:1019C00094F84710B4F848302046B047002884D037 +:1019D0004368A3630368E3631AE0B3F5106F36D07E +:1019E00040F6024293427FF478AF5C4BA36302233C +:1019F000E3630023C3E794F84630012B7FF46DAF17 +:101A0000B4F84C3023F00203C4E90E55A4F84C306E +:101A1000256478E7B4F84430B3F5A06F0ED194F89C +:101A2000463084F84E30204600F088FF63681B681B +:101A300013B1012120469847032323700023C4E9F2 +:101A40000E339CE704F14F03A3630123C3E723781C +:101A5000042B10D1302383F311882046FFF7C4FEF6 +:101A600085F311880321636884F84F5021701B6847 +:101A70000BB12046984794F84630002BDED084F80E +:101A80004F300423237063681B68002BD6D00221DB +:101A900020469847D2E794F848301D0603F00F011E +:101AA00020460AD500F0F6FF012804D002287FF472 +:101AB00014AF2B4B9AE72B4B98E700F0DDFFF3E7D1 +:101AC00094F84630002B7FF408AF94F8483013F0B8 +:101AD0000F01B3D01A06204602D501F0A9FAADE7EE +:101AE00001F09CFAAAE794F84630002B7FF4F5AE9B +:101AF00094F8483013F00F01A0D01B06204602D501 +:101B000001F082FA9AE701F075FA97E7142284F857 +:101B1000342083F311882B462A4629462046FFF7B6 +:101B20006DFE85F31188E9E65DB1152284F8342055 +:101B300083F311880021D4E90E232046FFF75EFECF +:101B4000FDE60B2284F8342083F311882B462A46C5 +:101B500029462046FFF764FEE3E700BF803B00080C +:101B6000783B00087C3B000838B590F834300446D8 +:101B7000002B3ED0063BDAB20F2A34D80F2B32D8D6 +:101B8000DFE803F037313108223231313131313180 +:101B900031313737C56BB0F84A309D4214D2C36833 +:101BA0001B8AB5FBF3F203FB12556DB9302383F3A7 +:101BB00011882B462A462946FFF732FE85F3118805 +:101BC0000A2384F834300EE0142384F834303023B0 +:101BD00083F3118800231A4619462046FFF70EFEAC +:101BE000002383F3118838BD036C03B198470023A9 +:101BF000E7E70021204601F007FA0021204601F026 +:101C0000F9F963681B6813B106212046984706233B +:101C1000D7E7000010B590F83430142B044629D0D3 +:101C200017D8062B05D001D81BB110BD093B022BDC +:101C3000FBD80021204601F0E7F90021204601F001 +:101C4000D9F963681B6813B106212046984706231B +:101C500019E0152BE9D10B2380F83430302383F3BE +:101C6000118800231A461946FFF7DAFD002383F393 +:101C70001188DAE7C3689B695B68002BD5D1036CD8 +:101C800003B19847002384F83430CEE7002303756E +:101C9000826803691B6899689142FBD25A680360A5 +:101CA00042601060586070470023037582680369C2 +:101CB0001B6899689142FBD85A68036042601060C3 +:101CC0005860704708B50846302383F311880B7DB0 +:101CD000032B05D0042B0DD02BB983F3118808BD3D +:101CE0008B6900221A604FF0FF338361FFF7CEFF4C +:101CF0000023F2E7D1E9003213605A60F3E70000F5 +:101D0000FFF7C4BF054BD9680875186802681A60E8 +:101D1000536001220275D860FEF7F4BA282600202D +:101D200030B50C4BDD684B1C87B004460FD02B46FA +:101D3000094A684600F04EF92046FFF7E3FF009B92 +:101D400013B1684600F050F9A86907B030BDFFF73D +:101D5000D9FFF9E728260020C51C0008044B1A68A3 +:101D6000DB6890689B68984294BF00200120704710 +:101D700028260020084B10B51C68D86822681A6015 +:101D8000536001222275DC60FFF78EFF014620467A +:101D9000BDE81040FEF7B6BA2826002038B5074C3B +:101DA00007490848012300252370656001F044FBC2 +:101DB0000223237085F3118838BD00BF90280020CE +:101DC000883B00082826002000F044B9034A5168E7 +:101DD00053685B1A9842FBD8704700BF001000E0C0 +:101DE0008B60022308618B82084670478368A3F1E9 +:101DF000840243F8142C026943F8442C426943F8E6 +:101E0000402C094A43F8242CC26843F8182C0222BB +:101E100003F80C2C002203F80B2C044A43F8102C76 +:101E2000A3F12000704700BF1D03000828260020F2 +:101E300008B5FFF7DBFFBDE80840FFF761BF000012 +:101E4000024BDB6898610F20FFF75CBF282600205B +:101E5000302383F31188FFF7F3BF000008B5014674 +:101E6000302383F311880820FFF75AFF002383F300 +:101E7000118808BD064BDB6839B1426818605A60AA +:101E8000136043600420FFF74BBF4FF0FF307047F3 +:101E9000282600200368984206D01A680260506025 +:101EA00099611846FFF72CBF7047000038B504460B +:101EB0000D462068844200D138BD036823605C6011 +:101EC0008561FFF71DFFF4E710B503689C68A24227 +:101ED0000CD85C688A600B604C602160596099681E +:101EE0008A1A9A604FF0FF33836010BD1B68121B83 +:101EF000ECE700000A2938BF0A2170B504460D46F8 +:101F00000A26601901F092FA01F07EFA041BA5423C +:101F100003D8751C2E460446F3E70A2E04D9BDE803 +:101F20007040012001F0C8BA70BD0000F8B5144B34 +:101F30000D46D96103F1100141600A2A19698260D6 +:101F400038BF0A22016048601861A818144601F0E1 +:101F50005FFA0A2701F058FA431BA342064606D34C +:101F60007C1C281901F062FA27463546F2E70A2F51 +:101F700004D9BDE8F840012001F09EBAF8BD00BFC9 +:101F800028260020F8B506460D4601F03DFA0F4A16 +:101F9000134653F8107F9F4206D12A460146304629 +:101FA000BDE8F840FFF7C2BFD169BB68441A2C19DD +:101FB00028BF2C46A34202D92946FFF79BFF2246A1 +:101FC00031460348BDE8F840FFF77EBF28260020D1 +:101FD0003826002010B4C0E9032300235DF8044B29 +:101FE0004361FFF7CFBF000010B5194C2369984239 +:101FF0000DD0D0E90032816813605A609A680A44B3 +:102000009A60002303604FF0FF33A36110BD2346A5 +:10201000026843F8102F53600022026022699A423E +:1020200003D1BDE8104001F0FBB9936881680B440F +:10203000936001F0E9F92269E1699268441AA242C9 +:10204000E4D91144BDE81040091AFFF753BF00BF9F +:10205000282600202DE9F047DFF8BC8008F11007A2 +:102060002C4ED8F8105001F0CFF9D8F81C40AA68CF +:10207000031B9A423ED81444D5E900324FF00009C0 +:10208000C8F81C4013605A60C5F80090D8F81030AA +:10209000B34201D101F0C4F989F31188D5E90331C4 +:1020A00028469847302383F311886B69002BD8D0DA +:1020B00001F0AAF96A69A0EB04094A4582460DD2EB +:1020C000022001F0F9F90022D8F81030B34208D10B +:1020D00051462846BDE8F047FFF728BF121A2244B0 +:1020E000F2E712EB090938BF4A4629463846FFF79E +:1020F000EBFEB5E7D8F81030B34208D01444211AEB +:10210000C8F81C00A960BDE8F047FFF7F3BEBDE8C2 +:10211000F08700BF382600202826002000207047C6 +:10212000FEE70000704700004FF0FF3070470000EE +:1021300002290CD0032904D00129074818BF002028 +:102140007047032A05D8054800EBC20070470448D1 +:1021500070470020704700BF603C00082C22002020 +:10216000143C000870B59AB00546084601A914460B +:1021700000F0C2F801A8FEF7B5FD431C5B00C5E9FD +:1021800000340022237003236370C6B201AB023413 +:102190001046D1B28E4204F1020401D81AB070BDCB +:1021A00013F8011B04F8021C04F8010C0132F0E7DB +:1021B00008B5302383F311880348FFF759FA002349 +:1021C00083F3118808BD00BF9828002090F84430A0 +:1021D00003F01F02012A07D190F845200B2A03D1F2 +:1021E0000023C0E90E3315E003F06003202B08D173 +:1021F000B0F848302BB990F84520212A03D81F2A7F +:1022000004D8FFF717BA222AEBD0FAE7034A826311 +:102210000722C26303640120704700BF232200200D +:1022200007B5052917D8DFE801F019160319192099 +:10223000302383F31188104A01900121FFF7BAFA85 +:1022400001980E4A0221FFF7B5FA0D48FFF7DCF9B5 +:10225000002383F3118803B05DF804FB302383F37C +:1022600011880748FFF7A6F9F2E7302383F31188B6 +:102270000348FFF7BDF9EBE7B43B0008D83B000883 +:102280009828002038B50C4D0C4C0D492A4604F115 +:102290000800FFF767FF05F1CA0204F110000949C1 +:1022A000FFF760FF05F5CA7204F118000649BDE8A2 +:1022B0003840FFF757BF00BF602D00202C220020C0 +:1022C000943B00089E3B0008A93B000870B50446FB +:1022D00008460D46FEF706FDC6B2204601340378D7 +:1022E0000BB9184670BD32462946FEF7E7FC0028B8 +:1022F000F3D10120F6E700002DE9F84F05460C4622 +:10230000FEF7F0FC2B49C6B22846FFF7DFFF08B105 +:102310000536F6B228492846FFF7D8FF08B110362F +:10232000F6B2632E0DD8DFF88C80DFF88C90234F47 +:10233000DFF890A0DFF890B02E7846B92670BDE89F +:10234000F88F29462046BDE8F84F01F0ABBB252E9B +:102350002BD1072241462846FEF7B0FC58B9DBF8DE +:1023600000302360DBF804306360DBF80830A360E2 +:1023700007350C34E0E7082249462846FEF79EFC64 +:1023800098B90F4BA21C197809090232C95D02F8ED +:10239000041C13F8011B01F00F015345C95D02F83D +:1023A000031CF0D118340835C6E704F8016B013579 +:1023B000C2E700BF803C0008A93B0008953C00082C +:1023C000107AFF1F1C7AFF1F883C0008BFF34F8F55 +:1023D000024AD368DB03FCD4704700BF003C0240D4 +:1023E00008B5094B1B7873B9FFF7F0FF074B1A6963 +:1023F000002ABFBF064A5A6002F188325A601A6842 +:1024000022F480621A6008BDBE2F0020003C02400A +:102410002301674508B50B4B1B7893B9FFF7D6FF2F +:10242000094B1A6942F000421A611A6842F480525C +:102430001A601A6822F480521A601A6842F48062A4 +:102440001A6008BDBE2F0020003C02400B28F0B5EA +:1024500016D80C4C0C4923787BB90C4D0E460C2336 +:102460004FF0006255F8047B46F8042B013B13F053 +:10247000FF033A44F6D10123237051F82000F0BD48 +:102480000020FCE7F02F0020C02F0020A83C00080F +:10249000014B53F820007047A83C00080C207047FF +:1024A0000B2810B5044601D9002010BDFFF7CEFF60 +:1024B000064B53F824301844C21A0BB90120F4E734 +:1024C00012680132F0D1043BF6E700BFA83C0008D7 +:1024D0000B2810B5044621D8FFF778FFFFF780FFDF +:1024E0000F4AF323D360C300DBB243F4007343F01D +:1024F00002031361136943F480331361FFF766FF2E +:10250000FFF7A4FF074B53F8241000F0D9F8FFF7AA +:1025100081FF2046BDE81040FFF7C2BF002010BD7C +:10252000003C0240A83C0008F8B512F00103144634 +:1025300042D18218B2F1016F57D82D4B1B6813F0AE +:10254000010352D02B4DFFF74BFFF323EB60FFF756 +:102550003DFF40F20127032C15D824F00104661832 +:10256000244C401A40F20117B142236900EB0105E7 +:1025700024D123F001032361FFF74CFF0120F8BDB4 +:10258000043C0430E7E78307E7D12B6923F4407369 +:102590002B612B693B432B6151F8046B0660BFF341 +:1025A0004F8FFFF713FF03689E42E9D02B6923F09A +:1025B00001032B61FFF72EFF0020E0E723F44073B7 +:1025C000236123693B4323610B882B80BFF34F8F2B +:1025D000FFF7FCFE2D8831F8023BADB2AB42C3D011 +:1025E000236923F001032361E4E71846C7E700BF2E +:1025F00000380240003C0240084908B50B7828B179 +:102600001BB9FFF7EDFE01230B7008BD002BFCD0BA +:10261000BDE808400870FFF7FDBE00BFBE2F0020D8 +:1026200010B50244064BD2B2904200D110BD441CFA +:1026300000B253F8200041F8040BE0B2F4E700BF09 +:10264000502800400F4B30B51C6F240407D41C6F7A +:1026500044F400741C671C6F44F400441C670A4C6B +:10266000236843F4807323600244084BD2B2904243 +:1026700000D130BD441C00B251F8045B43F8205037 +:10268000E0B2F4E7003802400070004050280040FB +:1026900007B5012201A90020FFF7C2FF019803B08E +:1026A0005DF804FB13B50446FFF7F2FFA04205D026 +:1026B000012201A900200194FFF7C4FF02B010BD60 +:1026C00070470000034B1A681AB9034AD2F87428FD +:1026D0001A607047F42F00200030024008B5FFF761 +:1026E000F1FF024B1868C0F3407008BDF42F0020C2 +:1026F00070470000FEE700000A4B0B480B4A90426F +:102700000BD30B4BDA1C121AC11E22F003028B42B0 +:1027100038BF00220021FEF7EDBA53F8041B40F841 +:10272000041BECE75C3E0008F0300020F030002095 +:10273000F030002070B5D0E915439E6800224FF0BC +:10274000FF3504EB42135101D3F800090028BEBF46 +:10275000D3F8000940F08040C3F80009D3F8000B1B +:102760000028BEBFD3F8000B40F08040C3F8000B38 +:10277000013263189642C3F80859C3F8085BE0D2E7 +:102780004FF00113C4F81C3870BD0000890141F0FE +:102790002001016103699B06FCD41220FFF716BBE0 +:1027A00010B5054C2046FEF7E5FF4FF0A0436365EA +:1027B000024BA36510BD00BFF82F0020FC3C0008B1 +:1027C00070B50378012B054650D12A4B446D9842D1 +:1027D0001BD1294B5A6B42F080025A635A6D42F06A +:1027E00080025A655A6D5A6942F080025A615A69EC +:1027F00022F080025A610E2143205B6900F022FC26 +:102800001E4BE3601E4BC4F800380023C4F8003EA2 +:10281000C02323606E6D4FF40413A3633369002B50 +:10282000FCDA012333610C20FFF7D0FA3369DB07B0 +:10283000FCD41220FFF7CAFA3369002BFCDA002619 +:10284000A6602846FFF776FF6B68C4F81068DB685F +:10285000C4F81468C4F81C684BB90A4BA3614FF064 +:10286000FF336361A36843F00103A36070BD064BAF +:10287000F4E700BFF82F0020003802404014004069 +:1028800003002002003C30C0083C30C0F8B5446D65 +:10289000054600212046FFF779FFA96D00234FF080 +:1028A00001128F68C4F834384FF00066C4F81C2851 +:1028B0004FF0FF3004EB431201339F42C2F800692E +:1028C000C2F8006BC2F80809C2F8080BF2D20B6814 +:1028D0006A6DEB65636210231361166916F01006CA +:1028E000FBD11220FFF772FAD4F8003823F4FE630C +:1028F000C4F80038A36943F4402343F01003A361F4 +:102900000923C4F81038C4F814380A4BEB604FF0B0 +:10291000C043C4F8103B084BC4F8003BC4F810692E +:10292000C4F80039EB6D03F1100243F48013EA653B +:10293000A362F8BDD83C000840800010426D90F8BA +:102940004E10D2F8003823F4FE6343EA0113C2F8B4 +:10295000003870472DE9F84300EB8103456DDA68D4 +:10296000166806F00306731E022B05EB41130C4696 +:1029700080460FFA81F94FEA41104FF00001C3F889 +:10298000101B4FF0010104F1100398BFB60401FAC7 +:1029900003F391698EBF334E06F1805606F500466B +:1029A00000293AD0578A04F15801490137436F5042 +:1029B000D5F81C180B43C5F81C382B180021C3F898 +:1029C000101953690127611EA7409BB3138A928B8C +:1029D0009B08012A88BF5343D8F85C20981842EA24 +:1029E000034301F1400205EB8202C8F85C00214676 +:1029F00053602846FFF7CAFE08EB8900C3681B8AAC +:102A000043EA8453483464011E432E51D5F81C38E0 +:102A10001F43C5F81C78BDE8F88305EB4917D7F8C4 +:102A2000001B21F40041C7F8001BD5F81C1821EA4F +:102A30000303C0E704F13F0305EB83030A4A5A602E +:102A400028462146FFF7A2FE05EB4910D0F80039D1 +:102A500023F40043C0F80039D5F81C3823EA0707EF +:102A6000D7E700BF0080001000040002826D1268EA +:102A7000C265FFF75FBE00005831436D49015B58E6 +:102A800013F4004004D013F4001F0CBF02200120F7 +:102A9000704700004831436D49015B5813F4004012 +:102AA00004D013F4001F0CBF022001207047000067 +:102AB00000EB8101CB68196A0B6813604B685360A7 +:102AC0007047000000EB810330B5DD68AA69136828 +:102AD000D36019B9402B84BF402313606B8A1468FC +:102AE000426D1C44013CB4FBF3F46343033323F015 +:102AF000030302EB411043EAC44343F0C043C0F870 +:102B0000103B2B6803F00303012B09B20ED1D2F85E +:102B1000083802EB411013F4807FD0F8003B14BF5B +:102B200043F0805343F00053C0F8003B02EB4112E6 +:102B3000D2F8003B43F00443C2F8003B30BD000034 +:102B40002DE9F041244D6E6D06EB40130446D3F899 +:102B5000087BC3F8087B38070AD5D6F8143819075C +:102B600006D505EB84032146DB6828465B68984759 +:102B7000FA071FD5D6F81438DB071BD505EB8403FD +:102B8000D968CCB98B69488A5A68B2FBF0F600FB69 +:102B900016228AB91868DA6890420DD2121AC3E96F +:102BA0000024302383F311880B482146FFF78AFF66 +:102BB00084F31188BDE8F081012303FA04F26B89E4 +:102BC00023EA02036B81CB68002BF3D02146024835 +:102BD000BDE8F041184700BFF82F002000EB81034B +:102BE00070B5DD68436D6C692668E6604A0156BBC6 +:102BF0001A444FF40020C2F810092A6802F00302B8 +:102C0000012A0AB20ED1D3F8080803EB421410F4DB +:102C1000807FD4F8000914BF40F0805040F000508D +:102C2000C4F8000903EB4212D2F8000940F0044056 +:102C3000C2F80009D3F83408012202FA01F1014375 +:102C4000C3F8341870BD19B9402E84BF40202060ED +:102C500020682E8A8419013CB4FBF6F440EAC44093 +:102C600040F000501A44C6E72DE9F8433B4D6E6D25 +:102C700006EB40130446D3F80889C3F8088918F016 +:102C8000010F4FEA40171AD0D6F81038DB0716D5D7 +:102C900005EB8003D9684B691868DA68904230D236 +:102CA000121A4FF000091A60C3F80490302383F31E +:102CB000118821462846FFF791FF89F3118818F003 +:102CC000800F1CD0D6F834380126A640334216D0E7 +:102CD00005EB84036D6DD3F80CC0DCF814200134CF +:102CE000E4B2D2F800E005EB04342F44516871459A +:102CF00015D3D5F8343823EA0606C5F83468BDE89C +:102D0000F883012303FA04F22B8923EA02032B81BF +:102D10008B68002BD3D0214628469847CFE7BCF8D4 +:102D20001000AEEB0103834228BF0346D7F8180911 +:102D300080B2B3EB800FE2D89068A0F1040959F893 +:102D4000048FC4F80080A0EB09089844B8F1040F80 +:102D5000F5D818440B4490605360C7E7F82F002063 +:102D60002DE9F74FA24C656D6E69AB691E4016F4F4 +:102D700080586E6107D02046FEF764FD03B0BDE8C1 +:102D8000F04F00F047BC002E12DAD5F8003E98480C +:102D90009B071EBFD5F8003E23F00303C5F8003E95 +:102DA000D5F8043823F00103C5F80438FEF774FDA4 +:102DB000370505D58E48FFF7BDFC8D48FEF75AFD57 +:102DC000B0040CD5D5F8083813F0060FEB6823F4DF +:102DD00070530CBF43F4105343F4A053EB6031071E +:102DE0001BD56368DB681BB9AB6923F00803AB61D3 +:102DF0002378052B0CD1D5F8003E7D489A071EBFDD +:102E0000D5F8003E23F00303C5F8003EFEF744FD6D +:102E10006368DB680BB176489847F30274D4B70255 +:102E200027D5D4F85490DFF8C8B100274FF0010A35 +:102E300009EB4712D2F8003B03F44023B3F5802F8F +:102E400011D1D2F8003B002B0DDA62890AFA07F3A0 +:102E500022EA0303638104EB8703DB68DB6813B1B9 +:102E6000394658469847A36D01379B68FFB29F4289 +:102E7000DED9F00617D5676D3A6AC2F30A1002F080 +:102E80000F0302F4F012B2F5802F00F08580B2F546 +:102E9000402F08D104EB83030022DB681B6A07F58F +:102EA000805790426AD13003D5F8184813D5E10312 +:102EB00002D50020FFF744FEA20302D50120FFF750 +:102EC0003FFE630302D50220FFF73AFE270302D537 +:102ED0000320FFF735FE75037FF550AFE00702D5FD +:102EE0000020FFF7C1FEA10702D50120FFF7BCFEBD +:102EF000620702D50220FFF7B7FE23077FF53EAF3A +:102F00000320FFF7B1FE39E7636DDFF8E4A001931A +:102F100000274FF00109A36D9B685FFA87FB9B4573 +:102F20003FF67DAF019B03EB4B13D3F8001901F47F +:102F30004021B1F5802F1FD1D3F8001900291BDAE9 +:102F4000D3F8001941F09041C3F80019D3F80019E3 +:102F50000029FBDB5946606DFFF718FC218909FA4F +:102F60000BF321EA0303238104EB8B03DB689B68EB +:102F700013B15946504698470137CCE7910708BF2F +:102F8000D7F80080072A98BF03F8018B02F10102ED +:102F900098BF4FEA182884E7023304EB830207F551 +:102FA00080575268D2F818C0DCF80820DCE9001C11 +:102FB000A1EB0C0C002188420AD104EB8304636866 +:102FC0009B699A6802449A605A6802445A606AE7A8 +:102FD00011F0030F08BFD7F800808C4588BF02F8B6 +:102FE000018B01F1010188BF4FEA1828E3E700BF18 +:102FF000F82F0020436D03EB4111D1F8003B43F45F +:103000000013C1F8003B7047436D03EB4111D1F849 +:10301000003943F40013C1F800397047436D03EBE6 +:103020004111D1F8003B23F40013C1F8003B704775 +:10303000436D03EB4111D1F8003923F40013C1F8BB +:103040000039704700F1604303F561430901C9B2DB +:1030500083F80013012200F01F039A4043099B00EC +:1030600003F1604303F56143C3F880211A607047A0 +:1030700030B5039C0172043304FB0325C0E90653F9 +:10308000049B03630021059BC160C0E90000C0E907 +:103090000422C0E90842C0E90A11436330BD0000C0 +:1030A000416A0022C0E90411C0E90A22C2606FF03F +:1030B0000101FEF7FBBE0000D0E90432934201D1CA +:1030C000C2680AB9181D704700207047036919606B +:1030D000C2680132C260C2691344826903619342CB +:1030E00024BF436A03610021FEF7D4BE38B504460D +:1030F0000D46E3683BB16269131D1268A362134475 +:10310000E362002007E0237A33B929462046FEF720 +:10311000B1FE0028EDDA38BD6FF00100FBE70000DA +:10312000C368C269013BC360436913448269436158 +:10313000934224BF436A436100238362036B03B15C +:103140001847704770B53023044683F31188866AA8 +:103150003EB9FFF7CBFF054618B186F31188284624 +:1031600070BDA36AE26A13F8015BA362934202D3C3 +:103170002046FFF7D5FF002383F31188EFE7000017 +:103180002DE9F84F04460E46174698464FF0300991 +:1031900089F311880025AA46D4F828B0BBF1000FA6 +:1031A00009D141462046FFF7A1FF20B18BF31188DA +:1031B0002846BDE8F88FD4E90A12A7EB050B521A8E +:1031C000934528BF9346BBF1400F1BD9334601F10D +:1031D000400251F8040B43F8040B9142F9D1A36A61 +:1031E00040334036A3624035D4E90A239A4202D3E1 +:1031F0002046FFF795FF8AF31188BD42D8D289F3A4 +:103200001188C9E730465A46FDF74EFDA36A5B4474 +:103210005E44A3625D44E7E710B5029C017204338B +:1032200003FB0421C0E906130023C0E90A33039B12 +:103230000363049BC460C0E90000C0E90422C0E944 +:103240000842436310BD0000026AC260426AC0E9DE +:1032500004220022C0E90A226FF00101FEF726BE17 +:10326000D0E904239A4201D1C26822B9184650F825 +:10327000043B0B60704700231846FAE7C368C26935 +:103280000133C3604369134482694361934224BF9D +:10329000436A43610021FEF7FDBD000038B50446D6 +:1032A0000D46E3683BB123691A1DA262E26913442B +:1032B000E362002007E0237A33B929462046FEF76F +:1032C000D9FD0028EDDA38BD6FF00100FBE7000002 +:1032D00003691960C268013AC260C2691344826915 +:1032E0000361934224BF436A036100238362036B3B +:1032F00003B118477047000070B530230D460446EF +:10330000114683F31188866A2EB9FFF7C7FF10B103 +:1033100086F3118870BDA36A1D70A36AE26A013347 +:103320009342A36204D3E16920460439FFF7D0FF3A +:10333000002080F31188EDE72DE9F84F04460D4693 +:10334000904699464FF0300A8AF311880026B3461A +:10335000A76A4FB949462046FFF7A0FF20B187F37F +:1033600011883046BDE8F88FD4E90A073A1AA8EB6D +:103370000607974228BF1746402F1BD905F1400387 +:1033800055F8042B40F8042B9D42F9D1A36A403331 +:10339000A3624036D4E90A239A4204D3E169204665 +:1033A0000439FFF795FF8BF311884645D9D28AF38C +:1033B0001188CDE729463A46FDF776FCA36A3B44DF +:1033C0003D44A3623E44E5E7D0E904239A4217D185 +:1033D000C3689BB1836A8BB1043B9B1A0ED0136008 +:1033E000C368013BC360C3691A44836902619A429E +:1033F00024BF436A03610023836201231846704798 +:103400000023FBE700F030B94FF08043586A704763 +:103410004FF08043002258631A610222DA6070473D +:103420004FF080430022DA60704700004FF0804385 +:1034300058637047FEE7000070B51B4B0163002521 +:10344000044686B0586085620E4600F0BFF804F16D +:103450001003C4E904334FF0FF33C4E90635C4E96F +:103460000044A560E562FFF7CFFF2B460246C4E9A2 +:10347000082304F134010D4A256580232046FEF718 +:10348000AFFC0123E0600A4A037500927268019262 +:10349000B268CDE90223074B6846CDE90435FEF753 +:1034A000C7FC06B070BD00BF90280020083D000892 +:1034B0000D3D000835340008024AD36A1843D06233 +:1034C000704700BF282600204B6843608B688360EC +:1034D000CB68C3600B6943614B6903628B694362CC +:1034E0000B6803607047000008B5264B26481A6930 +:1034F00040F2FF110A431A611A6922F4FF7222F0A6 +:1035000001021A611A691A6B0A431A631A6D0A4397 +:103510001A651E4A1B6D1146FFF7D6FF02F11C010A +:1035200000F58060FFF7D0FF02F1380100F5806000 +:10353000FFF7CAFF02F1540100F58060FFF7C4FFF6 +:1035400002F1700100F58060FFF7BEFF02F18C010F +:1035500000F58060FFF7B8FF02F1A80100F5806078 +:10356000FFF7B2FF02F1C40100F58060FFF7ACFF86 +:1035700002F1E00100F58060FFF7A6FFBDE808401A +:1035800000F0EEB80038024000000240143D000890 +:1035900008B500F067FAFEF701FCFFF793F8BDE805 +:1035A0000840FEF76FBE000070470000EFF309838C +:1035B00005494A6B22F001024A63683383F30988A4 +:1035C000002383F31188704700EF00E0302080F380 +:1035D000118862B60C4B0D4AD96821F4E0610904E8 +:1035E000090C0A43DA60D3F8FC20094942F08072E2 +:1035F000C3F8FC200A6842F001020A602022DA7750 +:1036000083F82200704700BF00ED00E00003FA05D8 +:10361000001000E010B5302383F311880E4B5B6877 +:1036200013F4006314D0F1EE103AEFF30984683C10 +:103630004FF08073E361094BDB6B236684F30988E9 +:10364000FEF78CFB10B1064BA36110BD054BFBE7E9 +:1036500083F31188F9E700BF00ED00E000EF00E020 +:103660002F030008320300080F4B1A6C42F00102CE +:103670001A641A6E42F001021A660C4A1B6E9368B5 +:1036800043F0010393604FF0804353229A624FF05E +:10369000FF32DA6200229A615A63DA605A600122CC +:1036A0005A611A60704700BF00380240002004E0F1 +:1036B0004FF0804208B51169D3680B40D9B2C943B5 +:1036C0009B07116107D5302383F31188FEF77CFB3C +:1036D000002383F3118808BD1F4B1A696FEAC25299 +:1036E0006FEAD2521A611A69C2F308021A614FF0E6 +:1036F000FF301A695A69586100215A6959615A693B +:103700001A6A62F080521A621A6A02F080521A62D1 +:103710001A6A5A6A58625A6A59625A6A1A6C42F0AC +:1037200080521A641A6E42F080521A661A6E0B4A60 +:10373000106840F480701060186F00F44070B0F5AD +:10374000007F1EBF4FF4803018671967536823F459 +:103750000073536000F05EB9003802400070004012 +:10376000334B4FF080521A64324A4FF4404111609B +:103770001A6842F001021A601A689107FCD59A682B +:1037800022F003029A602A4B9A6812F00C02FBD1D5 +:10379000196801F0F90119609A601A6842F48032E0 +:1037A0001A601A689203FCD55A6F42F001025A67F8 +:1037B0001F4B5A6F9007FCD51F4A5A601A6842F097 +:1037C00080721A601B4A53685904FCD5184B1A685A +:1037D0009201FCD5194A9A60194B1A68194B9A4202 +:1037E000194B21D1194A1168194A91421CD140F252 +:1037F00005121A60144A136803F00F03052BFAD15F +:103800000B4B9A6842F002029A609A6802F00C022E +:10381000082AFAD15A6C42F480425A645A6E42F431 +:1038200080425A665B6E704740F20572E1E700BF66 +:103830000038024000700040085440070094883867 +:10384000002004E011640020003C024000ED00E094 +:1038500041C20F41074A08B5536903F001035361A0 +:1038600023B1054A13680BB150689847BDE808407A +:10387000FFF7D0BE003C014070300020074A08B579 +:10388000536903F00203536123B1054A93680BB1F6 +:10389000D0689847BDE80840FFF7BCBE003C014037 +:1038A00070300020074A08B5536903F004035361E0 +:1038B00023B1054A13690BB150699847BDE8084028 +:1038C000FFF7A8BE003C014070300020074A08B551 +:1038D000536903F00803536123B1054A93690BB19F +:1038E000D0699847BDE80840FFF794BE003C01400E +:1038F00070300020074A08B5536903F01003536184 +:1039000023B1054A136A0BB1506A9847BDE80840D5 +:10391000FFF780BE003C014070300020164B10B510 +:103920005C6904F478725A61A30604D5134A936A59 +:103930000BB1D06A9847600604D5104A136B0BB1DF +:10394000506B9847210604D50C4A936B0BB1D06B92 +:103950009847E20504D5094A136C0BB1506C98479F +:10396000A30504D5054A936C0BB1D06C9847BDE80C +:103970001040FFF74FBE00BF003C014070300020F8 +:10398000194B10B55C6904F47C425A61620504D598 +:10399000164A136D0BB1506D9847230504D5134A91 +:1039A000936D0BB1D06D9847E00404D50F4A136EA8 +:1039B0000BB1506E9847A10404D50C4A936E0BB11D +:1039C000D06E9847620404D5084A136F0BB1506F4C +:1039D0009847230404D5054A936F0BB1D06F9847DD +:1039E000BDE81040FFF716BE003C014070300020DB +:1039F00008B50348FDF7C0FABDE80840FFF70ABE66 +:103A0000BC23002008B5FFF753FEBDE80840FFF7D0 +:103A100001BE0000062108B50846FFF713FB06218A +:103A20000720FFF70FFB06210820FFF70BFB0621FD +:103A30000920FFF707FB06210A20FFF703FB0621F9 +:103A40001720FFF7FFFA06212820FFF7FBFA0721CE +:103A50001C20FFF7F7FABDE808400C214720FFF7CC +:103A6000F1BA000008B5FFF737FE00F00DF8FDF7DA +:103A700097FCFDF77DFEFDF755FDFFF795FDBDE8D1 +:103A80000840FFF7BFBC00000023054A1946013378 +:103A9000102BC2E9001102F10802F8D1704700BFF3 +:103AA00070300020034611F8012B03F8012B002A87 +:103AB000F9D1704753544D3332463F3F3F00535482 +:103AC0004D3332463430780053544D33324634321D +:103AD000780053544D333246343436585800000081 +:103AE000012033000010410001105A00031059005A +:103AF0000710310000000000B43A00081304000071 +:103B0000BE3A000819040000C83A00082104000069 +:103B1000D23A0008009600000000000000000000FB +:103B20000000000000000000000000006113000819 +:103B30004D1300088913000875130008811300084D +:103B40006D13000859130008451300089513000869 +:103B500000000000A11400088D140008C91400081A +:103B6000B5140008C1140008AD1400089914000829 +:103B700085140008D51400080000000001000000B2 +:103B80000000000063300000843B00088026002015 +:103B9000902800204172647550696C6F7400254252 +:103BA0004F415244252D424C002553455249414C2A +:103BB000250000000200000000000000BD16000803 +:103BC0002917000840004000302D0020402D002023 +:103BD00002000000000000000300000000000000E0 +:103BE0006D1700080000000010000000502D00209C +:103BF000000000000100000000000000F82F00207D +:103C0000010102002122000831210008CD21000815 +:103C1000B1210008430000001C3C000809024300D9 +:103C2000020100C032090400000102020100052463 +:103C300000100105240100010424020205240600ED +:103C400001070582030800FF09040100020A0000C1 +:103C50000007050102400000070581024000000046 +:103C600012000000683C0008120110010200004030 +:103C70000912415700020102030100000403090474 +:103C800025424F41524425004A48454D5F4A484528 +:103C900046343035003031323334353637383941F7 +:103CA0004243444546000000004000000040000040 +:103CB0000040000000400000000001000000020081 +:103CC00000000200000002000000020000000200EC +:103CD000000002000000020000000000B11800080F +:103CE000691B0008151C00084000400058300020E7 +:103CF00058300020010000006830002080000000E3 +:103D000040010000030000006D61696E0069646C91 +:103D1000650000000000842A00000000AAAAAAAAE8 +:103D200000000024FFFD00000000000000A00A00C9 +:103D30004000001100000000AAAAAAAA4000001139 +:103D4000FFFF0000000000000000000000A00000D5 +:103D500000000000AAAAAAAA00500000FFFF00006D +:103D600000000088000000000000000000000000CB +:103D7000AAAAAAAA00000000FFFF0000000000009D +:103D8000000000000000000000000000AAAAAAAA8B +:103D900000000000FFFF0000000000000000000025 +:103DA0000000000000000000AAAAAAAA000000006B +:103DB000FFFF000000000000000000000000000005 +:103DC00000000000AAAAAAAA00000000FFFF00004D +:103DD00000000000000000000000000000000000E3 +:103DE0000A000000000000000300000000000000C6 +:103DF00000000000000000000000000000000000C3 +:103E000000000000000000000000000000000000B2 +:103E1000390400000000000000400F000000000016 +:103E2000FF00000098280020BC230020009600001E +:103E300000000800960000000008000004000000D8 +:103E40007C3C0008000000000000000000000000B2 +:0C3E500000000000000000000000000066 :00000001FF diff --git a/Tools/bootloaders/MatekF765-SE-bdshot_bl.bin b/Tools/bootloaders/MatekF765-SE-bdshot_bl.bin deleted file mode 100755 index 7a1c15e5fcf9d..0000000000000 Binary files a/Tools/bootloaders/MatekF765-SE-bdshot_bl.bin and /dev/null differ diff --git a/Tools/bootloaders/MatekF765-SE-bdshot_bl.hex b/Tools/bootloaders/MatekF765-SE-bdshot_bl.hex deleted file mode 100644 index c393e710b515d..0000000000000 --- a/Tools/bootloaders/MatekF765-SE-bdshot_bl.hex +++ /dev/null @@ -1,1034 +0,0 @@ -:020000040800F2 -:1000000000060220010200080302000803020008A3 -:1000100003020008030200080302000803020008AC -:10002000030200080302000803020008A1370008C9 -:10003000030200080302000803020008030200088C -:10004000030200080302000803020008030200087C -:100050000302000803020008453A00086D3A000850 -:10006000953A0008BD3A0008E53A00080302000886 -:10007000030200080302000803020008030200084C -:10008000030200080302000803020008030200083C -:100090000302000803020008030200080D3B0008E9 -:1000A000030200080302000803020008030200081C -:1000B000F53B0008030200080302000803020008E1 -:1000C00003020008030200080302000803020008FC -:1000D00003020008030200080302000803020008EC -:1000E000713B000803020008030200080302000835 -:1000F00003020008030200080302000803020008CC -:1001000003020008030200080302000803020008BB -:1001100003020008030200080302000803020008AB -:10012000030200080302000803020008030200089B -:10013000030200080302000803020008030200088B -:10014000030200080302000803020008192F000838 -:10015000030200080302000803020008030200086B -:10016000030200080302000803020008030200085B -:10017000030200080302000803020008030200084B -:100180000302000803020008E13B00080302000824 -:10019000030200080302000803020008030200082B -:1001A000030200080302000803020008030200081B -:1001B000030200080302000803020008030200080B -:1001C00003020008030200080302000803020008FB -:1001D00003020008030200080302000803020008EB -:1001E00003020008030200080302000803020008DB -:1001F00003020008030200080302000803020008CB -:1002000002E000F000F8FEE772B6374880F3088895 -:10021000364880F3098836483649086040F20000C5 -:10022000CCF200004EF63471CEF200010860BFF34C -:100230004F8FBFF36F8F40F20000C0F2F0004EF618 -:100240008851CEF200010860BFF34F8FBFF36F8F6C -:100250004FF00000E1EE100A4EF63C71CEF20001C4 -:100260000860062080F31488BFF36F8F02F0B2FAA3 -:1002700003F028FA4FF055301F491B4A91423CBF0A -:1002800041F8040BFAE71D49184A91423CBF41F876 -:10029000040BFAE71A491B4A1B4B9A423EBF51F81E -:1002A000040B42F8040BF8E700201849184A914261 -:1002B0003CBF41F8040BFAE702F0CAFA03F062FA15 -:1002C000144C154DAC4203DA54F8041B8847F9E787 -:1002D00000F042F8114C124DAC4203DA54F8041B02 -:1002E0008847F9E702F0B2BA000602200022022095 -:1002F0000000000808ED00E00000022000060220D7 -:1003000010400008002202206422022068220220FD -:100310003835022000020008000200080002000830 -:10032000000200082DE9F04F2DED108AC1F80CD025 -:10033000D0F80CD0BDEC108ABDE8F08F002383F319 -:1003400011882846A047002001F0F2FDFEE701F0E9 -:1003500081FD00DFFEE7000038B500F0B7FB02F0DA -:10036000F9F9054602F02CFA0446D0B90F4B9D422C -:1003700019D001339D4241F2883512BF0446002551 -:100380000124002002F0F0F90CB100F077F800F041 -:1003900071FD00F017FC284600F0FAF800F06EF846 -:1003A000F9E70025EDE70546EBE700BF010007B0E0 -:1003B00008B500F0D3FBA0F120035842584108BD16 -:1003C00007B541F21203022101A8ADF8043000F094 -:1003D000E3FB03B05DF804FB38B5302383F31188E9 -:1003E000174803680BB101F06FFE0023154A4FF464 -:1003F0007A71134801F05EFE002383F31188124CDA -:10040000236813B12368013B2360636813B16368F9 -:10041000013B63600D4D2B7833B963687BB90220D3 -:1004200000F0A2FC322363602B78032B07D16368B2 -:100430002BB9022000F098FC4FF47A73636038BD4A -:1004400068220220D903000888230220802202208B -:10045000084B187003280CD8DFE800F008050208E4 -:10046000022000F077BC022000F06ABC024B0022A0 -:100470005A6070478022022088230220F8B53F4B43 -:100480003F4A1C461968013177D004339342F9D1B1 -:100490006268A24271D33B4B9B6803F1006303F592 -:1004A000C0339A4269D2002000F0A6FB0220FFF779 -:1004B000CFFF354B00211A6C19641A6E19661A6E3B -:1004C0005A6C59645A6E59665A6E5A6942F08002E3 -:1004D0005A615A6922F080025A615A691A6942F0D7 -:1004E00000521A611A6922F000521A611B6972B631 -:1004F0004FF0E023C3F8084DD4E90004BFF34F8F59 -:10050000BFF36F8F214AC2F88410BFF34F8F536936 -:1005100023F480335361BFF34F8FD2F8803043F61A -:10052000E076C3F3C905C3F34E335B0103EA060C5F -:1005300029464CEA81770139C2F87472F9D2203B1E -:1005400013F1200FF2D1BFF34F8FBFF36F8FBFF3C3 -:100550004F8FBFF36F8F536923F400335361002330 -:10056000C2F85032BFF34F8FBFF36F8F302383F346 -:100570001188854680F308882047F8BD008001086F -:1005800020800108002202200038024000ED00E037 -:100590002DE9F04F93B0B44B2022FF2100900AA820 -:1005A0009D6800F011FCB14A1378A3B90121B0484D -:1005B00011700360302383F3118803680BB101F0DD -:1005C00083FD0023AB4A4FF47A71A94801F072FD14 -:1005D000002383F31188009B13B1A74B009A1A6084 -:1005E000A64A1378032B03D000231370A24A53604A -:1005F0004FF0000A009CD3465646D146012000F039 -:10060000A9FB24B19C4B1B68002B00F02682002024 -:1006100000F0A4FA0390039B002BF2DB012000F012 -:100620008FFB039B213B1F2BE8D801A252F823F03C -:10063000B1060008D90600086D070008FD0500088E -:10064000FD050008FD050008FF070008CF090008A8 -:10065000E90800084B090008730900089909000817 -:10066000FD050008AB090008FD0500081D0A00088B -:1006700051070008FD050008610A0008BD060008D2 -:1006800051070008FD0500084B090008FD0500089A -:10069000FD050008FD050008FD050008FD05000832 -:1006A000FD050008FD050008FD0500086D070008B0 -:1006B0000220FFF77DFE002840F0F981009B022117 -:1006C00005A8BAF1000F08BF1C4641F21233ADF87D -:1006D000143000F061FA91E74FF47A7000F03EFABE -:1006E000071EEBDB0220FFF763FE0028E6D0013F88 -:1006F000052F00F2DE81DFE807F0030A0D10133644 -:100700000523042105A8059300F046FA17E004210B -:100710005548F9E704215A48F6E704215948F3E718 -:100720004FF01C08404608F1040800F067FA042165 -:10073000059005A800F030FAB8F12C0FF2D1012095 -:100740004FF0000900FA07F747EA0B0B5FFA8BFB43 -:1007500000F086FB26B10BF00B030B2B08BF002427 -:10076000FFF72EFE4AE704214748CDE7002EA5D02B -:100770000BF00B030B2BA1D10220FFF719FE07464C -:1007800000289BD00120002600F036FA0220FFF757 -:100790005FFE1FFA86F8404600F03EFA0446B0B10C -:1007A000039940460136A1F140025142514100F007 -:1007B00043FA0028EDD1BA46044641F21213022151 -:1007C00005A83E46ADF8143000F0E6F916E72546D8 -:1007D0000120FFF73DFE244B9B68AB4207D928461A -:1007E00000F00CFA013040F067810435F3E7002592 -:1007F000224BBA463E461D701F4B5D60A8E7002E97 -:100800003FF45CAF0BF00B030B2B7FF457AF0220D0 -:10081000FFF71EFE322000F0A1F9B0F10008FFF64C -:100820004DAF18F003077FF449AF0F4A08EB0503FB -:10083000926893423FF642AFB8F5807F3FF73EAFF4 -:10084000124BB845019323DD4FF47A7000F086F91E -:100850000390039A002AFFF631AF039A0137019BF8 -:1008600003F8012BEDE700BF0022022084230220C1 -:1008700068220220D9030008882302208022022057 -:1008800004220220082202200C22022084220220BC -:10089000C820FFF78DFD074600283FF40FAF1F2D3E -:1008A00011D8C5F120020AAB25F003008449424566 -:1008B000184428BF4246019200F060FA019AFF21D5 -:1008C0007F4800F081FA4FEAA803C8F387027C4909 -:1008D0002846019300F080FA064600283FF46DAFE9 -:1008E000019B05EB830533E70220FFF761FD00283C -:1008F0003FF4E4AE00F0CCF900283FF4DFAE00276F -:10090000B846704B9B68BB4218D91F2F11D80A9B61 -:1009100001330ED027F0030312AA134453F8203CEE -:1009200005934046042205A9043700F003FB8046E6 -:10093000E7E7384600F062F90590F2E7CDF8148059 -:10094000042105A800F028F902E70023642104A887 -:10095000049300F017F900287FF4B0AE0220FFF7EF -:1009600027FD00283FF4AAAE049800F079F905901D -:10097000E6E70023642104A8049300F003F90028AB -:100980007FF49CAE0220FFF713FD00283FF496AEE3 -:10099000049800F075F9EAE70220FFF709FD002846 -:1009A0003FF48CAE00F084F9E1E70220FFF700FD90 -:1009B00000283FF483AE05A9142000F07FF9074614 -:1009C0000421049004A800F0E7F83946B9E7322082 -:1009D00000F0C4F8071EFFF671AEBB077FF46EAEE1 -:1009E000384A07EB0903926893423FF667AE02204C -:1009F000FFF7DEFC00283FF461AE27F003074F4409 -:100A0000B9453FF4A5AE484609F1040900F0F6F8EF -:100A10000421059005A800F0BFF8F1E74FF47A70C3 -:100A2000FFF7C6FC00283FF449AE00F031F900287A -:100A300044D00A9B01330BD008220AA9002000F001 -:100A4000CBF900283AD02022FF210AA800F0BCF9F7 -:100A5000FFF7B6FC1C4801F071FA13B0BDE8F08F47 -:100A6000002E3FF42BAE0BF00B030B2B7FF426AEC6 -:100A70000023642105A8059300F084F807460028A8 -:100A80007FF41CAE0220FFF793FC804600283FF461 -:100A900015AEFFF795FC41F2883001F04FFA05984A -:100AA00000F026FA46463C4600F0DAF9A6E506468E -:100AB0004EE64FF0000901E6BA467EE637467CE690 -:100AC0008422022000220220A0860100704700003C -:100AD0002DE9F84F4FF47A7306460D46002402FBC9 -:100AE00003F7DFF85080DFF8509098F900305FFA94 -:100AF00084FA5A1C01D0A34212D159F824002A4684 -:100B000031460368D3F820B03B46D847854207D129 -:100B1000074B012083F800A0BDE8F88F0124E4E72B -:100B2000002CFBD04FF4FA7001F008FA0020F3E734 -:100B3000D4230220102202201422022070B5044681 -:100B40004FF47A76412C254628BF412506FB05F057 -:100B500001F0F4F9641BF5D170BD0000002307B566 -:100B6000024601210DF107008DF80730FFF7B0FFB5 -:100B700020B19DF8070003B05DF804FB4FF0FF3093 -:100B8000F9E700000A46042108B5FFF7A1FF80F04D -:100B90000100C0B2404208BD074B0A4630B4197884 -:100BA000064B53F82140014623682046DD69044B7B -:100BB000AC4630BC604700BFD42302201422022080 -:100BC000A086010070B50A4E00240A4D01F0C8FC51 -:100BD000308028683388834208D901F0BBFC2B6839 -:100BE00004440133B4F5C03F2B60F2D370BD00BFA5 -:100BF000D62302209023022001F060BD00F10060A6 -:100C000000F5C0300068704700F10060920000F508 -:100C1000C03001F0EBBC0000054B1A68054B1B8887 -:100C20009B1A834202D9104401F094BC0020704703 -:100C300090230220D623022038B50446074D29B15F -:100C400028682044BDE8384001F0A4BC286820444E -:100C500001F088FC0028F3D038BD00BF90230220AB -:100C600010F0030309D1B0F5846F04D200F10050F5 -:100C7000A0F571200368184670470023FBE70000C9 -:100C800000F10050A0F57120D0F82004704700005A -:100C9000064991F8243033B100230822086A81F80C -:100CA0002430FFF7B1BF0120704700BF942302201A -:100CB000014B1868704700BF002004E01E4B01384C -:100CC000F0B51D680A1803231C482E0CC5F30B044D -:100CD00035460788A7420BD144680B46013C934236 -:100CE00018461BD214F9010F48B103F8010BF6E7BF -:100CF000013B00F10800ECD191420ED20B461846A0 -:100D00002C24B6F5805F00F8014B0AD1824202D94B -:100D10004122981C5A70401AF0BD0846B6F5805F13 -:100D2000F9D041F201039D42F5D18242F3D95A2311 -:100D300000F8013BEFE700BF002004E01C22022086 -:100D4000022803D1024B4FF080629A61704700BFC6 -:100D5000000C0240022803D1024B4FF480629A61DA -:100D6000704700BF000C0240022804D1024A5369B8 -:100D700083F4806353617047000C0240002310B578 -:100D8000934203D0CC5CC4540133F9E710BD00009A -:100D9000013810B510F9013F3BB191F900409C4278 -:100DA00003D11AB10131013AF4E71AB191F90020E7 -:100DB000981A10BD1046FCE703460246D01A12F9F5 -:100DC000011B0029FAD1704702440346934202D026 -:100DD00003F8011BFAE770472DE9F8431F4D14464D -:100DE0000746884695F8242052BBDFF870909CB3E4 -:100DF00095F824302BB92022FF2148462F62FFF7B7 -:100E0000E3FF95F824004146C0F1080205EB80009D -:100E1000A24228BF2246D6B29200FFF7AFFF95F854 -:100E20002430A41B17441E449044E4B2F6B2082EAA -:100E300085F82460DBD1FFF72BFF0028D7D108E02D -:100E40002B6A03EB82038342CFD0FFF721FF0028F8 -:100E5000CBD10020BDE8F8830120FBE794230220DA -:100E6000024B1A78024B1A70704700BFD42302203D -:100E70001022022038B5194C194D204600F0BCFB59 -:100E80002946204600F0E4FB2D684FF47A70EA6EA4 -:100E9000D2F8043843F00203C2F80438FFF74EFEDC -:100EA0001049284600F0DCFCEA6E0F4DD2F80438F9 -:100EB000286823F002030D49A042C2F804384FF419 -:100EC000E1330B6001D000F0F7FA6868A04204D06B -:100ED0000649BDE8384000F0EFBA38BDB828022016 -:100EE000BC3D0008C43D000814220220BC2302209F -:100EF0000C4B70B50C4D04461E780C4B55F8262053 -:100F00009A420DD00A4B002118221846FFF75CFFC9 -:100F10000460014655F82600BDE8704000F0CCBAE8 -:100F200070BD00BFD423022014220220B828022062 -:100F3000BC23022030B50A44084D91420DD011F86F -:100F4000013B5840082340F30004013B2C4013F0C0 -:100F5000FF0384EA5000F6D1EFE730BD2083B8EDFF -:100F6000026843681143016003B1184770470000ED -:100F7000024A136843F0C0031360704700780040D2 -:100F800013B50E4C204600F08BFA04F11400002338 -:100F90004FF480720A49009400F048F9094B4FF46D -:100FA0008072094904F13800009400F0C1F9074A41 -:100FB000074BC4E9172302B010BD00BFD82302209D -:100FC00044240220710F00084425022000780040CC -:100FD00080F93703037C30B5214C002918BF0C463B -:100FE000012B0CD11F4B984209D11F4B1A6C42F0B8 -:100FF00080421A641A6E42F080421A661B6E2268A2 -:10100000036EC16D03EB52038466B3FBF2F36268B7 -:10101000150442BF23F0070503F0070343EA450325 -:10102000CB60A36843F040034B60E36843F00103E7 -:101030008B6042F4967343F001030B604FF0FF3373 -:101040000B62510505D512F0102205D0B2F1805F78 -:1010500004D080F8643030BD7F23FAE73F23F8E7FF -:10106000D03C0008D8230220003802402DE9F04788 -:10107000C66D05463768F469210734621AD014F04A -:10108000080118BF4FF48071E20748BF41F020010A -:10109000A3074FF0300348BF41F04001600748BF4D -:1010A00041F0800183F31188281DFFF759FF0023C9 -:1010B00083F31188E2050AD5302383F311884FF4B6 -:1010C0008061281DFFF74CFF002383F311884FF048 -:1010D00030094FF0000A14F0200838D13B0616D52D -:1010E0004FF0300905F1380A200610D589F3118830 -:1010F000504600F051F9002836DA0821281DFFF784 -:101100002FFF27F080033360002383F311887906D3 -:1011100014D5620612D5302383F31188D5E9132341 -:101120009A4208D12B6C33B127F040071021281DBB -:10113000FFF716FF3760002383F31188E30618D505 -:10114000AA6E1369ABB15069BDE8F047184789F33F -:101150001188736A284695F86410194000F0BAF9AE -:101160008AF31188F469B6E7B06288F31188F469EC -:10117000BAE7BDE8F0870000F8B515468268044676 -:101180000B46AA4200D28568A1692669761AB54243 -:101190000BD218462A46FFF7F1FDA3692B44A36141 -:1011A0002846A3685B1BA360F8BD0CD9AF1B18468B -:1011B0003246FFF7E3FD3A46E1683044FFF7DEFDD3 -:1011C000E3683B44EBE718462A46FFF7D7FDE368A0 -:1011D000E5E7000083689342F7B50446154600D260 -:1011E0008568D4E90460361AB5420BD22A46FFF767 -:1011F000C5FD63692B4463612846A3685B1BA3603C -:1012000003B0F0BD0DD93246AF1B0191FFF7B6FD1B -:1012100001993A46E0683144FFF7B0FDE3683B448A -:10122000E9E72A46FFF7AAFDE368E4E710B50A44B8 -:101230000024C361029B8460C16002610362C0E953 -:101240000000C0E9051110BD08B5D0E90532934290 -:1012500001D1826882B98268013282605A1C42617F -:1012600019700021D0E904329A4224BFC368436157 -:1012700000F080FE002008BD4FF0FF30FBE70000CB -:1012800070B5302304460E4683F31188A568A5B1D6 -:10129000A368A269013BA360531CA361157822696E -:1012A000934224BFE368A361E3690BB120469847EA -:1012B000002383F31188284607E03146204600F0DA -:1012C00049FE0028E2DA85F3118870BD2DE9F74F59 -:1012D00004460E4617469846D0F81C904FF0300A48 -:1012E0008AF311884FF0000B154665B12A46314646 -:1012F0002046FFF741FF034660B94146204600F013 -:1013000029FE0028F1D0002383F31188781B03B055 -:10131000BDE8F08FB9F1000F03D001902046C84717 -:10132000019B8BF31188ED1A1E448AF31188DCE7C8 -:10133000C160C361009B82600362C0E90511114472 -:10134000C0E9000001617047F8B504460D46164635 -:10135000302383F31188A768A7B1A368013BA3607A -:1013600063695A1C62611D70D4E904329A4224BF39 -:10137000E3686361E3690BB120469847002080F37E -:10138000118807E03146204600F0E4FD0028E2DA4B -:1013900087F31188F8BD0000D0E9052310B59A4203 -:1013A00001D182687AB982680021013282605A1CB8 -:1013B00082611C7803699A4224BFC368836100F08C -:1013C000D9FD204610BD4FF0FF30FBE72DE9F74F68 -:1013D00004460E4617469846D0F81C904FF0300A47 -:1013E0008AF311884FF0000B154665B12A46314645 -:1013F0002046FFF7EFFE034660B94146204600F065 -:10140000A9FD0028F1D0002383F31188781B03B0D5 -:10141000BDE8F08FB9F1000F03D001902046C84716 -:10142000019B8BF31188ED1A1E448AF31188DCE7C7 -:10143000026843681143016003B118477047000018 -:101440001430FFF743BF00004FF0FF331430FFF7B5 -:101450003DBF00003830FFF7B9BF00004FF0FF3349 -:101460003830FFF7B3BF00001430FFF709BF0000AA -:101470004FF0FF311430FFF703BF00003830FFF7A3 -:1014800063BF00004FF0FF323830FFF75DBF000050 -:10149000012914BF6FF0130000207047FFF770BDE3 -:1014A000044B036000234360C0E90233012303744B -:1014B000704700BFE83C000810B53023044683F3B2 -:1014C0001188FFF787FD02230020237480F3118821 -:1014D00010BD000038B5C36904460D461BB9042190 -:1014E0000844FFF7A5FF294604F11400FFF7ACFEFE -:1014F000002806DA201D4FF40061BDE83840FFF7F0 -:1015000097BF38BD026843681143016003B11847B3 -:101510007047000013B5446BD4F8A4381A681178EA -:10152000042915D1217C022912D1197901231289AC -:101530008B4013420CD101A904F14C0001F07EFF55 -:10154000D4F8A4480246019B2179206800F0D6F91E -:1015500002B010BD143001F001BF00004FF0FF33A6 -:10156000143001F0FBBE00004C3001F0D3BF00008E -:101570004FF0FF334C3001F0CDBF0000143001F0CC -:10158000CFBE00004FF0FF31143001F0C9BE0000A3 -:101590004C3001F09FBF00004FF0FF324C3001F0A3 -:1015A00099BF000000207047D0F8A4381A6810B521 -:1015B00011780446042917D1017C022914D15979E4 -:1015C000012352898B4013420ED1143001F062FE88 -:1015D000024648B1D4F8A4484FF48073617920687A -:1015E000BDE8104000F078B910BD0000406BFFF777 -:1015F000DBBF0000704700007FB5124B01250426B9 -:10160000044603600023057400F184024360294608 -:10161000C0E902330C4B0290143001934FF48073F5 -:10162000009601F013FE094B04F29442294604F19E -:101630004C000294CDE900634FF4807301F0DAFEB0 -:1016400004B070BD103D0008ED1500081515000828 -:101650000B68302282F311880A7903EB8202106250 -:101660004A790D3243F822008A7912B103EB8203E2 -:1016700018620223C0F8A4180374002080F31188B4 -:101680007047000038B5037F044613B190F854301A -:10169000ABB90125201D0221FFF734FF04F114002E -:1016A0006FF00101257700F071FC04F14C0084F823 -:1016B00054506FF00101BDE8384000F067BC38BD00 -:1016C00010B5012104460430FFF71CFF00232377E7 -:1016D00084F8543010BD000038B50446002514309D -:1016E00001F0CCFD04F14C00257701F09BFE201D9C -:1016F00084F854500121FFF705FF2046BDE838402B -:10170000FFF752BF90F85C3003F06003202B06D146 -:1017100090F85D200023212A03D81F2A06D8002034 -:101720007047222AFBD1C0E9143303E0034A026563 -:101730000722426583650120704700BF34220220E2 -:10174000D0F8A43837B51A680446117804291AD19C -:10175000017C022917D11979012312898B40134288 -:1017600011D100F14C05284601F01CFF58B101A928 -:10177000284601F063FED4F8A4480246019B217973 -:10178000206800F0BBF803B030BD000000EB81031F -:10179000F0B51E6A85B004460D46FEB1302383F3D2 -:1017A000118804EB8507301D0821FFF7ABFEFB68AD -:1017B00006F14C005B691B681BB1019001F04CFE07 -:1017C000019803A901F03AFE024648B1039B29465D -:1017D000204600F093F8002383F3118805B0F0BD94 -:1017E000FB685A691268002AF5D01B8A013B134036 -:1017F000F1D104F15C02EAE70D3138B550F821402F -:10180000DCB1302383F31188D4F8A428136852790B -:1018100003EB8203DB689B695D6845B104216018B6 -:10182000FFF770FE294604F1140001F03DFD20464B -:10183000FFF7BAFE002383F3118838BD704700001C -:1018400001F08AB801232822002110B5044600F8CF -:10185000243BFFF7B9FA0023C4E9013310BD0000AF -:1018600038B50446302383F3118800254160C0E970 -:101870000355C0E90555C0E9075501F07DF802237D -:10188000237085F31188284638BD000070B500EB41 -:101890008103054650690E461446DA6018B11022DD -:1018A0000021FFF791FAA06918B110220021FFF77B -:1018B0008BFA31462846BDE8704001F027B9000098 -:1018C000826802F0011282600022C0E90422C0E9AD -:1018D0000622026201F0A6B9F0B4012500EB8104F2 -:1018E00047898D40E4683D43A46945812360002316 -:1018F000A2606360F0BC01F0C1B90000F0B4012542 -:1019000000EB810407898D40E4683D4364690581EB -:1019100023600023A2606360F0BC01F03BBA0000CA -:1019200070B502230025044603704566056280F801 -:101930004C50C0E90255C0E90455C0E9065501F014 -:1019400081F863681B6823B129462046BDE87040D2 -:10195000184770BD0378052B10B504460AD080F8EF -:1019600068300523037043681B680BB10421984756 -:101970000023A36010BD00000178052906D190F86E -:101980006820436802701B6803B118477047000065 -:1019900070B590F84C30044613B1002380F84C30F9 -:1019A00004F15C02204601F05FF963689B68B3B9FB -:1019B00094F85C3013F0600535D00021204601F02A -:1019C00011FC0021204601F003FC63681B6813B181 -:1019D000062120469847062384F84C3070BD2046E7 -:1019E00098470028E4D0B4F86230626D9A4288BF0C -:1019F000636594F95C30656D002B4FF0300380F225 -:101A00000381002D00F0F280092284F84C2083F33A -:101A1000118800212046D4E91423FFF76FFF00232B -:101A200083F31188DAE794F85D2003F07F0343EA3B -:101A3000022340F20232934200F0C58021D8B3F570 -:101A4000807F48D00DD8012B3FD0022B00F093802F -:101A5000002BB2D104F16402226502226265A36503 -:101A6000C1E7B3F5817F00F09B80B3F5407FA4D13F -:101A700094F85E30012BA0D1B4F8643043F0020337 -:101A800032E0B3F5006F4DD017D8B3F5A06F31D069 -:101A9000A3F5C063012B90D86368204694F85E20BC -:101AA0005E6894F85F10B4F86030B047002884D0C6 -:101AB00043682365036863651AE0B3F5106F36D099 -:101AC00040F6024293427FF478AF5C4B23650223D9 -:101AD00063650023C3E794F85E30012B7FF46DAF9C -:101AE000B4F8643023F00203A4F86430C4E9145558 -:101AF000A56578E7B4F85C30B3F5A06F0ED194F823 -:101B00005E30204684F8663000F0F4FF63681B689E -:101B100013B1012120469847032323700023C4E911 -:101B200014339CE704F1670323650123C3E723789B -:101B3000042B10D1302383F311882046FFF7C0FE19 -:101B400085F311880321636884F8675021701B684E -:101B50000BB12046984794F85E30002BDED084F815 -:101B600067300423237063681B68002BD6D00221E2 -:101B700020469847D2E794F8603020461D0603F0CF -:101B80000F010AD501F062F8012804D002287FF481 -:101B900014AF2B4B9AE72B4B98E701F049F8F3E78A -:101BA00094F85E30002B7FF408AF94F8603013F0A7 -:101BB0000F01B3D01A06204602D501F027FBADE78E -:101BC00001F01AFBAAE794F85E30002B7FF4F5AE23 -:101BD00094F8603013F00F01A0D01B06204602D508 -:101BE00001F000FB9AE701F0F3FA97E7142284F87A -:101BF0004C2083F311882B462A4629462046FFF7BE -:101C00006BFE85F31188E9E65DB1152284F84C205E -:101C100083F3118800212046D4E91423FFF75CFEEA -:101C2000FDE60B2284F84C2083F311882B462A46CC -:101C300029462046FFF762FEE3E700BF403D00086B -:101C4000383D00083C3D000838B590F84C3004465B -:101C5000002B3ED0063BDAB20F2A34D80F2B32D8F5 -:101C6000DFE803F03731310822323131313131319F -:101C700031313737456DB0F862309D4214D2C368B8 -:101C80001B8AB5FBF3F203FB12556DB9302383F3C6 -:101C900011882B462A462946FFF730FE85F3118826 -:101CA0000A2384F84C300EE0142384F84C3030239F -:101CB00083F31188002320461A461946FFF70CFECD -:101CC000002383F3118838BD836D03B19847002347 -:101CD000E7E70021204601F085FA0021204601F0C7 -:101CE00077FA63681B6813B10621204698470623DC -:101CF000D7E7000010B590F84C300446142B29D0DB -:101D000017D8062B05D001D81BB110BD093B022BFB -:101D1000FBD80021204601F065FA0021204601F0A1 -:101D200057FA63681B6813B10621204698470623BB -:101D300019E0152BE9D10B2380F84C30302383F3C5 -:101D4000118800231A461946FFF7D8FD002383F3B4 -:101D50001188DAE7C3689B695B68002BD5D1836D76 -:101D600003B19847002384F84C30CEE70023826803 -:101D7000037503691B6899689142FBD25A68036036 -:101D800042601060586070470023826803750369E1 -:101D90001B6899689142FBD85A68036042601060E2 -:101DA0005860704708B50846302383F311880B7DCF -:101DB000032B05D0042B0DD02BB983F3118808BD5C -:101DC0008B6900221A604FF0FF338361FFF7CEFF6B -:101DD0000023F2E7D1E9003213605A60F3E7000014 -:101DE000FFF7C4BF054BD9680875186802685360CF -:101DF0001A600122D8600275FEF794BA48260220C4 -:101E00000C4B30B5DD684B1C87B004460FD02B4619 -:101E1000094A684600F04EF92046FFF7E3FF009BB1 -:101E200013B1684600F050F9A86907B030BDFFF75C -:101E3000D9FFF9E748260220A51D0008044B1A68BF -:101E4000DB6890689B68984294BF0020012070472F -:101E500048260220084B10B51C68D86822685360D9 -:101E60001A600122DC602275FFF78EFF01462046D2 -:101E7000BDE81040FEF756BA4826022038B5074C98 -:101E800001230025064907482370656001F0C2FB65 -:101E90000223237085F3118838BD00BFB0280220CB -:101EA000483D00084826022000F044B9034A516822 -:101EB00053685B1A9842FBD8704700BF001000E0DF -:101EC0008B600223086108468B8270478368A3F108 -:101ED000840243F8142C026943F8442C426943F805 -:101EE000402C094A43F8242CC268A3F1200043F88F -:101EF000182C022203F80C2C002203F80B2C034AA6 -:101F000043F8102C704700BF3D030008482602200C -:101F100008B5FFF7DBFFBDE80840FFF761BF000031 -:101F2000024BDB6898610F20FFF75CBF4826022058 -:101F3000302383F31188FFF7F3BF000008B5014693 -:101F4000302383F311880820FFF75AFF002383F31F -:101F5000118808BD064BDB6839B1426818605A60C9 -:101F6000136043600420FFF74BBF4FF0FF30704712 -:101F7000482602200368984206D01A680260506022 -:101F800018469961FFF72CBF7047000038B504462A -:101F90000D462068844200D138BD036823605C6030 -:101FA0008561FFF71DFFF4E7036810B59C68A24246 -:101FB0000CD85C688A600B604C602160596099683D -:101FC0008A1A9A604FF0FF33836010BD121B1B68A2 -:101FD000ECE700000A2938BF0A2170B504460D4617 -:101FE0000A26601901F010FB01F0FCFA041BA5425F -:101FF00003D8751C04462E46F3E70A2E04D90120A7 -:10200000BDE8704001F046BB70BD0000F8B5144B50 -:102010000D460A2A4FF00A07D96103F110018260C8 -:1020200038BF0A224160196914460160486018618E -:10203000A81801F0DBFA01F0D5FA431B0646A342CB -:1020400006D37C1C28192746354601F0DDFAF2E755 -:102050000A2F04D90120BDE8F84001F01BBBF8BDF0 -:1020600048260220F8B506460D4601F0BBFA0F4A95 -:10207000134653F8107F9F4206D12A460146304648 -:10208000BDE8F840FFF7C2BFD169BB68441A2C19FC -:1020900028BF2C46A34202D92946FFF79BFF2246C0 -:1020A00031460348BDE8F840FFF77EBF48260220CE -:1020B00058260220C0E90323002310B45DF8044B26 -:1020C0004361FFF7CFBF000010B5194C2369984258 -:1020D0000DD08168D0E9003213605A609A680A44D2 -:1020E0009A60002303604FF0FF33A36110BD0268C4 -:1020F000234643F8102F53600022026022699A425F -:1021000003D1BDE8104001F079BA936881680B44AF -:10211000936001F067FA2269E1699268441AA24269 -:10212000E4D91144BDE81040091AFFF753BF00BFBE -:10213000482602202DE9F047DFF8BC8008F110079F -:102140002C4ED8F8105001F04DFAD8F81C40AA686F -:10215000031B9A423ED814444FF00009D5E90032DF -:10216000C8F81C4013605A60C5F80090D8F81030C9 -:10217000B34201D101F042FA89F31188D5E9033164 -:1021800028469847302383F311886B69002BD8D0F9 -:1021900001F028FA6A69A0EB040982464A450DD28B -:1021A000022001F077FA0022D8F81030B34208D1AB -:1021B00051462846BDE8F047FFF728BF121A2244CF -:1021C000F2E712EB09092946384638BF4A46FFF7BD -:1021D000EBFEB5E7D8F81030B34208D01444C8F885 -:1021E0001C00211AA960BDE8F047FFF7F3BEBDE867 -:1021F000F08700BF582602204826022000207047A2 -:10220000FEE70000704700004FF0FF30704700000D -:1022100002290CD0032904D00129074818BF002047 -:102220007047032A05D8054800EBC20070470448F0 -:1022300070470020704700BF203E00084422022063 -:10224000D43D000870B59AB005460846144601A969 -:1022500000F0C2F801A8FEF7AFFD431C0022C6B291 -:102260005B001046C5E9003423700323023404F8F0 -:10227000013C01ABD1B202348E4201D81AB070BD1C -:1022800013F8011B013204F8010C04F8021CF1E7F9 -:1022900008B5302383F311880348FFF751FA002370 -:1022A00083F3118808BD00BFB828022090F85C3085 -:1022B00003F01F02012A07D190F85D200B2A03D1F9 -:1022C0000023C0E9143315E003F06003202B08D18C -:1022D000B0F860302BB990F85D20212A03D81F2A6E -:1022E00004D8FFF70FBA222AEBD0FAE7034A0265B7 -:1022F0000722426583650120704700BF3B22022010 -:1023000007B5052917D8DFE801F0191603191920B8 -:10231000302383F31188104A01210190FFF7B6FAA8 -:10232000019802210D4AFFF7B1FA0D48FFF7D4F9E1 -:10233000002383F3118803B05DF804FB302383F39B -:1023400011880748FFF79EF9F2E7302383F31188DD -:102350000348FFF7B5F9EBE7743D0008983D000826 -:10236000B828022038B50C4D0C4C2A460C4904F113 -:102370000800FFF767FF05F1CA0204F110000949E0 -:10238000FFF760FF05F5CA7204F118000649BDE8C1 -:102390003840FFF757BF00BF90310220442202208F -:1023A000543D00085E3D0008693D000870B50446D4 -:1023B00008460D46FEF700FDC6B2204601340378FC -:1023C0000BB9184670BD32462946FEF7E1FC0028DD -:1023D000F3D10120F6E700002DE9F04705460C4651 -:1023E000FEF7EAFC2C49C6B22846FFF7DFFF08B12A -:1023F0000C36F6B229492846FFF7D8FF08B1103647 -:10240000F6B2632E0BD8DFF89080DFF89090244F5F -:10241000DFF898A02E7846B92670BDE8F0872946E7 -:102420002046BDE8F04701F035BC252E30D107220B -:1024300041462846FEF7ACFC80B91A4B224603F110 -:10244000100153F8040B8B4242F8040BF9D11988A0 -:1024500007359B78133411809370DBE708224946D7 -:102460002846FEF795FC98B9A21C0F4B197802324A -:102470000909C95D02F8041C13F8011B01F00F01E2 -:102480005345C95D02F8031CF0D118340835C1E783 -:10249000013504F8016BBDE7403E0008693D0008C6 -:1024A0005C3E0008483E000820F4F01F2CF4F01FAA -:1024B000BFF34F8F024AD368DB03FCD4704700BFE1 -:1024C000003C024008B5074B1B7853B9FFF7F0FFFB -:1024D000054B1A69002A04DA044A5A6002F188326C -:1024E0005A6008BDEE330220003C024023016745DC -:1024F00008B5054B1B7833B9FFF7DAFF034A1369B8 -:1025000043F00043136108BDEE330220003C02405B -:102510000B28F0B516D80C4C0C4923787BB90E4625 -:102520000B4D0C234FF00062013B55F8047B46F83D -:10253000042B13F0FF033A44F6D10123237051F822 -:102540002000F0BD0020FCE720340220F033022000 -:10255000703E0008014B53F820007047703E0008A1 -:102560000C2070470B2810B5044601D9002010BD7F -:10257000FFF7CEFF064B53F824301844C21A0BB9AC -:102580000120F4E712680132F0D1043BF6E700BF06 -:10259000703E00080B2810B5044621D8FFF788FFCD -:1025A000FFF790FF0F4AF323D360C300DBB243F47D -:1025B000007343F002031361136943F48033136122 -:1025C000FFF776FFFFF7A4FF074B53F8241000F046 -:1025D000D9F82046FFF78CFFBDE81040FFF7C2BFD7 -:1025E000002010BD003C0240703E0008F8B512F01B -:1025F0000103144642D18218B2F1026F57D82D4B15 -:102600001B6813F0010352D0FFF75CFF2A4DF32340 -:1026100040F20127EB60FFF74BFF032C15D824F0A5 -:102620000104401A40F201176618234CB14200EB36 -:102630000105236924D123F0010301202361FFF761 -:1026400057FFF8BD043C0430E7E78307E7D12B6967 -:1026500023F440732B612B693B432B6151F8046BCE -:102660000660BFF34F8FFFF723FF03689E42E9D058 -:102670002B6923F001032B61FFF73AFF0020E0E70D -:1026800023F44073236123693B4323610B882B8030 -:10269000BFF34F8FFFF70CFF2D88ADB231F8023B2F -:1026A000AB42C3D0236923F001032361E4E718465A -:1026B000C7E700BF00380240003C0240084908B5A7 -:1026C0000B7828B11BB9FFF7FDFE01230B7008BD85 -:1026D000002BFCD00870BDE80840FFF709BF00BF21 -:1026E000EE3302200244074BD2B210B5904200D123 -:1026F00010BD441C00B253F8200041F8040BE0B2B6 -:10270000F4E700BF502800400F4B30B51C6F240485 -:1027100007D41C6F44F400741C671C6F44F400441D -:102720001C670A4C02442368D2B243F480732360CE -:10273000074B904200D130BD441C51F8045B00B2FD -:1027400043F82050E0B2F4E7003802400070004047 -:102750005028004007B5012201A90020FFF7C2FF61 -:10276000019803B05DF804FB13B50446FFF7F2FFD0 -:10277000A04205D0012201A900200194FFF7C4FF67 -:1027800002B010BD0144BFF34F8F064B884204D303 -:10279000BFF34F8FBFF36F8F7047C3F85C022030D9 -:1027A000F4E700BF00ED00E0034B1A681AB9034AD2 -:1027B000D2F874281A607047243402200030024096 -:1027C00008B5FFF7F1FF024B1868C0F3407008BD71 -:1027D0002434022070B5BFF34F8FBFF36F8F1A4AB6 -:1027E0000021C2F85012BFF34F8FBFF36F8F5369B0 -:1027F00043F400335361BFF34F8FBFF36F8FC2F8C1 -:102800008410BFF34F8FD2F8803043F6E074C3F3E7 -:10281000C900C3F34E335B0103EA0406014646EAEE -:1028200081750139C2F86052F9D2203B13F1200FB3 -:10283000F2D1BFF34F8F536943F480335361BFF339 -:102840004F8FBFF36F8F70BD00ED00E0FEE700001B -:10285000214B2248224A70B5904237D3214BC11EEA -:10286000DA1C121A22F003028B4238BF0022002128 -:10287000FEF7AAFA1C4A0023C2F88430BFF34F8F38 -:10288000D2F8803043F6E074C3F3C900C3F34E338B -:102890005B0103EA0406014646EA81750139C2F884 -:1028A0006C52F9D2203B13F1200FF2D1BFF34F8FBE -:1028B000BFF36F8FBFF34F8FBFF36F8F0023C2F84B -:1028C0005032BFF34F8FBFF36F8F70BD53F8041BAF -:1028D00040F8041BC0E700BF7440000838350220F0 -:1028E000383502203835022000ED00E070B5D0E91F -:1028F0001B4300224FF0FF359E6804EB4213510149 -:10290000D3F80009002805DAD3F8000940F0804028 -:10291000C3F80009D3F8000B002805DAD3F8000B40 -:1029200040F08040C3F8000B013263189642C3F8B0 -:102930000859C3F8085BE0D24FF00113C4F81C3803 -:1029400070BD0000890141F02001016103699B060F -:10295000FCD41220FFF7AABA10B5054C2046FEF7AA -:1029600071FF4FF0A043E366024B236710BD00BF29 -:1029700028340220C43E000870B503780546012BB8 -:1029800050D12A4BC46E98421BD1294B0E214320B3 -:102990005A6B42F080025A635A6D42F080025A65C7 -:1029A0005A6D5A6942F080025A615A6922F08002D7 -:1029B0005A615B6900F034FC1E4BE3601E4BC4F8A7 -:1029C00000380023EE6EC4F8003EC02323604FF4AD -:1029D0000413A3633369002BFCDA01230C20336159 -:1029E000FFF764FA3369DB07FCD41220FFF75EFAC5 -:1029F0003369002BFCDA00262846A660FFF776FF35 -:102A00006B68C4F81068DB68C4F81468C4F81C6804 -:102A10004BB90A4BA3614FF0FF336361A36843F0E6 -:102A20000103A36070BD064BF4E700BF2834022009 -:102A3000003802404014004003002002003C30C037 -:102A4000083C30C0F8B5C46E054600214FF0006662 -:102A50002046FFF777FF296F00234FF001128F68A0 -:102A60004FF0FF30C4F83438C4F81C2804EB43128C -:102A700001339F42C2F80069C2F8006BC2F808092E -:102A8000C2F8080BF2D20B68EA6E6B676362102320 -:102A90001361166916F01006FBD11220FFF706FA33 -:102AA000D4F8003823F4FE63C4F80038A36943F473 -:102AB000402343F01003A3610923C4F81038C4F87D -:102AC00014380A4BEB604FF0C043C4F8103B084B7E -:102AD000C4F8003BC4F81069C4F800396B6F03F107 -:102AE000100243F480136A67A362F8BDA03E000899 -:102AF00040800010C26E90F86610D2F8003823F4BF -:102B0000FE6343EA0113C2F8003870472DE9F84329 -:102B100000EB8103C56E0C468046DA680FFA81F936 -:102B20004801166806F00306731E022B05EB4113DD -:102B30004FF0000194BFB604384EC3F8101B4FF09D -:102B4000010104F1100398BF06F1805601FA03F366 -:102B5000916998BF06F5004600293AD0578A04F1DA -:102B60005801374349016F50D5F81C180B43002119 -:102B7000C5F81C382B180127C3F81019A740536952 -:102B8000611E9BB3138A928B9B08012A88BF534313 -:102B9000D8F87420981842EA034301F14002214614 -:102BA000C8F87400284605EB82025360FFF7CAFE9E -:102BB00008EB8900C3681B8A43EA845348341E43E8 -:102BC00064012E51D5F81C381F43C5F81C78BDE8A8 -:102BD000F88305EB4917D7F8001B21F40041C7F82B -:102BE000001BD5F81C1821EA0303C0E704F13F03DA -:102BF0000B4A2846214605EB83035A60FFF7A2FEE5 -:102C000005EB4910D0F8003923F40043C0F800392F -:102C1000D5F81C3823EA0707D7E700BF008000106B -:102C200000040002026F12684267FFF75FBE0000F7 -:102C30005831C36E49015B5813F4004004D013F4BB -:102C4000001F0CBF02200120704700004831C36EF6 -:102C500049015B5813F4004004D013F4001F0CBF6B -:102C6000022001207047000000EB8101CB68196A47 -:102C70000B6813604B6853607047000000EB8103E2 -:102C800030B5DD68AA691368D36019B9402B84BFD9 -:102C9000402313606B8A1468C26E1C4402EB41101F -:102CA000013C09B2B4FBF3F46343033323F00303A1 -:102CB00043EAC44343F0C043C0F8103B2B6803F021 -:102CC0000303012B0ED1D2F8083802EB411013F4A4 -:102CD000807FD0F8003B14BF43F0805343F0005393 -:102CE000C0F8003B02EB4112D2F8003B43F0044332 -:102CF000C2F8003B30BD00002DE9F041244D0446F0 -:102D0000EE6E06EB4013D3F8087B3807C3F8087B58 -:102D10000AD5D6F81438190706D505EB84032146E1 -:102D20002846DB685B689847FA071FD5D6F8143841 -:102D3000DB071BD505EB8403D968CCB98B69488ABE -:102D40005A68B2FBF0F600FB16228AB91868DA68F6 -:102D500090420DD2121AC3E90024302383F3118864 -:102D60000B482146FFF78AFF84F31188BDE8F08104 -:102D7000012303FA04F26B8923EA02036B81CB6817 -:102D8000002BF3D021460248BDE8F041184700BFB0 -:102D90002834022000EB81034A0170B5DD68C36E60 -:102DA0006C692668E66056BB1A444FF40020C2F8EE -:102DB00010092A6802F00302012A0AB20ED1D3F8E0 -:102DC000080803EB421410F4807FD4F8000914BF04 -:102DD00040F0805040F00050C4F8000903EB42126C -:102DE000D2F8000940F00440C2F800090122D3F8EB -:102DF000340802FA01F10143C3F8341870BD19B95F -:102E0000402E84BF4020206020681A442E8A8419F6 -:102E1000013CB4FBF6F440EAC44040F00050C6E781 -:102E20002DE9F8433B4D04464701EE6E06EB401397 -:102E3000D3F8088918F0010FC3F808891AD0D6F81A -:102E40001038DB0716D505EB8003D9684B69186885 -:102E5000DA68904230D2121A4FF000091A60C3F8B3 -:102E60000490302383F3118821462846FFF792FF10 -:102E700089F3118818F0800F1CD0D6F83438012659 -:102E8000A640334216D005EB84030134ED6ED3F82F -:102E90000CC0E4B22F44DCF8142005EB0434D2F863 -:102EA00000E05168714515D3D5F8343823EA060699 -:102EB000C5F83468BDE8F883012303FA04F22B89CE -:102EC00023EA02032B818B68002BD3D021462846AE -:102ED0009847CFE7AEEB0103BCF81000834228BF50 -:102EE0000346D7F8180980B2B3EB800FE2D8906898 -:102EF000A0F1040959F8048FC4F80080A0EB090878 -:102F00009844B8F1040FF5D818440B44906053600E -:102F1000C7E700BF283402202DE9F74FA44CE56E27 -:102F20006E69AB691E4016F480586E6107D020466A -:102F3000FEF7F6FC03B0BDE8F04F00F069BC002ED0 -:102F400012DAD5F8003E9B0705D0D5F8003E23F0F5 -:102F50000303C5F8003ED5F80438954823F0010373 -:102F6000C5F80438FEF708FD370505D59048FFF78A -:102F7000BDFC8F48FEF7EEFCB0040CD5D5F8083840 -:102F800013F0060FEB6823F470530CBF43F4105397 -:102F900043F4A053EB6031071BD56368DB681BB9B2 -:102FA000AB6923F00803AB612378052B0CD1D5F86E -:102FB000003E9A0705D0D5F8003E23F00303C5F87C -:102FC000003E7B48FEF7D8FC6368DB680BB17848AD -:102FD0009847F30200F18980B70227D5D4F86C90A6 -:102FE00000274FF0010ADFF8C8B109EB4712D2F809 -:102FF000003B03F44023B3F5802F11D1D2F8003BFE -:10300000002B0DDA62890AFA07F322EA03036381CF -:1030100004EB8703DB68DB6813B1394658469847F1 -:103020000137236FFFB29B689F42DED9F00617D5A8 -:10303000E76E3A6AC2F30A1002F00F0302F4F012CC -:10304000B2F5802F00F09880B2F5402F08D104EB44 -:103050008303002207F58057DB681B6A90427ED10C -:103060003303D5F818481DD5E70302D50020FFF734 -:1030700043FEA50302D50120FFF73EFE600302D503 -:103080000220FFF739FE210302D50320FFF734FEAB -:10309000E20202D50420FFF72FFEA30202D505208D -:1030A000FFF72AFE77037FF545AFE60702D500203C -:1030B000FFF7B6FEA50702D50120FFF7B1FE6007B6 -:1030C00002D50220FFF7ACFE210702D50320FFF74F -:1030D000A7FEE20602D50420FFF7A2FEA3067FF5B5 -:1030E00029AF0520FFF79CFE24E7E36E00274FF091 -:1030F0000109DFF8BCA00193236F5FFA87FB9B688F -:103100009B453FF669AF019B03EB4B13D3F80019C6 -:1031100001F44021B1F5802F1FD1D3F80019002907 -:103120001BDAD3F8001941F09041C3F80019D3F825 -:1031300000190029FBDB5946E06EFFF703FC2189EB -:1031400009FA0BF321EA0303238104EB8B03DB6809 -:103150009B6813B15946504698470137CCE7910711 -:1031600001D1D7F80080072A02F101029CBF03F8C1 -:10317000018B4FEA182871E7023307F5805704EBFB -:1031800083025268D2F818C0DCF80820DCE9001C81 -:10319000A1EB0C0C002188420CD104EB8304636882 -:1031A0009B699A6802449A605A6802445A6057E7D9 -:1031B0002834022011F0030F01D1D7F800808C458C -:1031C00001F1010184BF02F8018B4FEA1828E2E700 -:1031D000C36E03EB4111D1F8003B43F40013C1F877 -:1031E000003B7047C36E03EB4111D1F8003943F443 -:1031F0000013C1F800397047C36E03EB4111D1F8D9 -:10320000003B23F40013C1F8003B7047C36E03EB8F -:103210004111D1F8003923F40013C1F80039704787 -:10322000090100F16043012203F56143C9B283F84B -:10323000001300F01F039A4043099B0003F1604311 -:1032400003F56143C3F880211A60704730B5043339 -:10325000039C0172002104FB0325C160C0E90653F1 -:10326000049B0363059BC0E90000C0E90422C0E998 -:103270000842C0E90A11436330BD00000022416AE0 -:10328000C260C0E90411C0E90A226FF00101FEF733 -:103290007DBE0000D0E90432934201D1C2680AB970 -:1032A000181D704700207047036919600021C2682B -:1032B0000132C260C269134482699342036124BF30 -:1032C000436A0361FEF756BE38B504460D46E3680F -:1032D0003BB162690020131D1268A3621344E362CC -:1032E00007E0237A33B929462046FEF733FE00284B -:1032F000EDDA38BD6FF00100FBE70000C368C2697A -:10330000013BC3604369134482699342436124BF14 -:10331000436A436100238362036B03B1184770471C -:1033200070B53023044683F31188866A3EB9FFF7EF -:10333000CBFF054618B186F31188284670BDA36AF5 -:10334000E26A13F8015B9342A36202D32046FFF7BF -:10335000D5FF002383F31188EFE700002DE9F84F34 -:1033600004460E46174698464FF0300989F31188F7 -:103370000025AA46D4F828B0BBF1000F09D1414678 -:103380002046FFF7A1FF20B18BF311882846BDE846 -:10339000F88FD4E90A12A7EB050B521A934528BF00 -:1033A0009346BBF1400F1BD9334601F1400251F85F -:1033B000040B914243F8040BF9D1A36A403640351F -:1033C0004033A362D4E90A239A4202D32046FFF78E -:1033D00095FF8AF31188BD42D8D289F31188C9E7D5 -:1033E00030465A46FDF7CAFCA36A5E445D445B441E -:1033F000A362E7E710B5029C0433017203FB0421CA -:10340000C460C0E906130023C0E90A33039B0363C9 -:10341000049BC0E90000C0E90422C0E908424363FC -:1034200010BD0000026A6FF00101C260426AC0E98B -:1034300004220022C0E90A22FEF7A8BDD0E9042335 -:103440009A4201D1C26822B9184650F8043B0B6079 -:10345000704700231846FAE7C3680021C2690133A8 -:10346000C3604369134482699342436124BF436A42 -:103470004361FEF77FBD000038B504460D46E368A2 -:103480003BB1236900201A1DA262E2691344E36282 -:1034900007E0237A33B929462046FEF75BFD002872 -:1034A000EDDA38BD6FF00100FBE700000369196039 -:1034B000C268013AC260C2691344826993420361DF -:1034C00024BF436A036100238362036B03B118477F -:1034D0007047000070B530230D460446114683F353 -:1034E0001188866A2EB9FFF7C7FF10B186F31188DD -:1034F00070BDA36A1D70A36AE26A01339342A3629E -:1035000004D3E16920460439FFF7D0FF002080F39F -:103510001188EDE72DE9F84F04460D46904699468F -:103520004FF0300A8AF311880026B346A76A4FB9D4 -:1035300049462046FFF7A0FF20B187F311883046A7 -:10354000BDE8F88FD4E90A073A1AA8EB06079742B4 -:1035500028BF1746402F1BD905F1400355F8042B0F -:103560009D4240F8042BF9D1A36A40364033A36250 -:10357000D4E90A239A4204D3E16920460439FFF7CB -:1035800095FF8BF311884645D9D28AF31188CDE790 -:1035900029463A46FDF7F2FBA36A3D443E443B44CC -:1035A000A362E5E7D0E904239A4217D1C3689BB12F -:1035B000836A8BB1043B9B1A0ED01360C368013B36 -:1035C000C360C3691A4483699A42026124BF436A93 -:1035D0000361002383620123184670470023FBE741 -:1035E00000F040B94FF08043586A70474FF0804375 -:1035F000002258631A610222DA6070474FF080435C -:103600000022DA60704700004FF080435863704733 -:10361000FEE7000070B51B4B0025044686B05860DD -:103620000E468562016300F0CBF804F11003A5603B -:10363000E562C4E904334FF0FF33C4E90044C4E950 -:103640000635FFF7CFFF2B46024604F13401204632 -:10365000C4E9082380230C4A2565FEF731FC0123C9 -:103660000A4AE06000920375684672680192B26887 -:10367000CDE90223064BCDE90435FEF749FC06B03F -:1036800070BD00BFB0280220D03E0008D53E000823 -:1036900011360008024AD36A1843D062704700BF4F -:1036A000482602204B6843608B688360CB68C36008 -:1036B0000B6943614B6903628B6943620B6803606A -:1036C0007047000008B52C4B40F2FF712B481A6977 -:1036D0000A431A611A6922F4FF6222F007021A6192 -:1036E0001A691A6B0A431A631A6D0A431A65244A47 -:1036F0001B6D1146FFF7D6FF00F5806002F11C013B -:10370000FFF7D0FF00F5806002F13801FFF7CAFF34 -:1037100000F5806002F15401FFF7C4FF00F58060FE -:1037200002F17001FFF7BEFF00F5806002F18C012D -:10373000FFF7B8FF00F5806002F1A801FFF7B2FFC4 -:1037400000F5806002F1C401FFF7ACFF00F5806076 -:1037500002F1E001FFF7A6FF00F5806002F1FC0135 -:10376000FFF7A0FF02F58C7100F58060FFF79AFF6C -:10377000BDE8084000F0ECB800380240000002400C -:10378000DC3E000808B500F065FAFEF777FBFFF7AE -:103790000BF8BDE80840FEF7E5BD000070470000EB -:1037A000EFF30983054968334A6B22F001024A634B -:1037B00083F30988002383F31188704700EF00E04A -:1037C000302080F3118862B60D4B0E4AD96821F47F -:1037D000E0610904090C0A430B49DA60D3F8FC20C4 -:1037E00042F08072C3F8FC20084AC2F8B01F11688A -:1037F00041F0010111602022DA7783F8220070473E -:1038000000ED00E00003FA0555CEACC5001000E065 -:10381000302310B583F311880E4B5B6813F40063FB -:1038200014D0F1EE103AEFF309844FF08073683C46 -:10383000E361094BDB6B236684F30988FEF7FEFA2C -:1038400010B1064BA36110BD054BFBE783F3118854 -:10385000F9E700BF00ED00E000EF00E04F030008D3 -:10386000520300080F4B1A6C42F001021A641A6EE0 -:1038700042F001021A660C4A1B6E936843F0010382 -:1038800093604FF080436B229A624FF0FF32DA620E -:1038900000229A615A63DA605A6001225A611A6002 -:1038A000704700BF00380240002004E04FF0804223 -:1038B00008B51169D3680B40D9B29B076FEA0101C3 -:1038C000116107D5302383F31188FEF7EDFA002349 -:1038D00083F3118808BD00001B4B4FF0FF3000211F -:1038E0001A696FEA42526FEA52521A611A69C2F3B8 -:1038F0000A021A611A695A6958615A6959615A6902 -:103900001A6A62F080521A621A6A02F080521A62CF -:103910001A6A5A6A58625A6A59625A6A0B4A106895 -:1039200040F480701060186F00F44070B0F5007FB4 -:1039300003D04FF4803018671967536823F400737D -:10394000536000F05FB900BF0038024000700040D3 -:10395000364B4FF44041364A1A64364A11601A68B1 -:1039600042F001021A601A689207FCD59A6822F0A8 -:1039700003029A602D4B9A6812F00C02FBD1196871 -:1039800001F0F90119609A601A6842F480321A60F5 -:103990001A689003FCD55A6F42F001025A67234B14 -:1039A0005A6F9107FCD5244A5A601A6842F0807217 -:1039B0001A60204B5A685204FCD51A6842F48032CF -:1039C0001A605A68D003FCD51A6842F400321A60B3 -:1039D000184A53689903FCD5144B1A689201FCD518 -:1039E000164A9A6040F20112C3F88C200022C3F8F4 -:1039F000902040F20733124A1360136803F00F035C -:103A0000072BFAD1094B9A6842F002029A609A6831 -:103A100002F00C02082AFAD15A6C42F480425A642D -:103A20005A6E42F480425A665B6E7047003802401C -:103A30000004001000700040086C400900948838B1 -:103A4000003C0240074A08B5536903F00103536183 -:103A500023B1054A13680BB150689847BDE8084088 -:103A6000FFF7D6BE003C0140B8340220074A08B533 -:103A7000536903F00203536123B1054A93680BB104 -:103A8000D0689847BDE80840FFF7C2BE003C01403F -:103A9000B8340220074A08B5536903F004035361A0 -:103AA00023B1054A13690BB150699847BDE8084036 -:103AB000FFF7AEBE003C0140B8340220074A08B50B -:103AC000536903F00803536123B1054A93690BB1AD -:103AD000D0699847BDE80840FFF79ABE003C014016 -:103AE000B8340220074A08B5536903F01003536144 -:103AF00023B1054A136A0BB1506A9847BDE80840E4 -:103B0000FFF786BE003C0140B8340220164B10B5CA -:103B10005C6904F478725A61A30604D5134A936A67 -:103B20000BB1D06A9847600604D5104A136B0BB1ED -:103B3000506B9847210604D50C4A936B0BB1D06BA0 -:103B40009847E20504D5094A136C0BB1506C9847AD -:103B5000A30504D5054A936C0BB1D06C9847BDE81A -:103B60001040FFF755BE00BF003C0140B8340220B2 -:103B7000194B10B55C6904F47C425A61620504D5A6 -:103B8000164A136D0BB1506D9847230504D5134A9F -:103B9000936D0BB1D06D9847E00404D50F4A136EB6 -:103BA0000BB1506E9847A10404D50C4A936E0BB12B -:103BB000D06E9847620404D5084A136F0BB1506F5A -:103BC0009847230404D5054A936F0BB1D06F9847EB -:103BD000BDE81040FFF71CBE003C0140B834022095 -:103BE00008B50348FDF742FABDE80840FFF710BEEC -:103BF000D823022008B5FFF759FEBDE80840FFF7BB -:103C000007BE0000062108B50846FFF709FB06219C -:103C10000720FFF705FB06210820FFF701FB06211F -:103C20000920FFF7FDFA06210A20FFF7F9FA06211D -:103C30001720FFF7F5FA06212820FFF7F1FA0721F0 -:103C40001C20FFF7EDFA0C215220BDE80840FFF7D9 -:103C5000E7BA000008B5FFF73FFE00F00DF8FDF7EA -:103C60001DFCFDF7EDFDFDF7C5FCFFF797FDBDE879 -:103C70000840FFF7B5BC00000023054A1946013390 -:103C8000102BC2E9001102F10802F8D1704700BF01 -:103C9000B8340220034611F8012B03F8012B002A47 -:103CA000F9D1704753544D3332463F3F3F3F3F3F7A -:103CB0000053544D333246375B347C355D780053C6 -:103CC000544D333246375B367C375D780000000058 -:103CD000009600000000000000000000000000004E -:103CE0000000000000000000000000005D1400085B -:103CF0004914000885140008711400087D14000898 -:103D000069140008551400084114000891140008B3 -:103D100000000000711500085D15000899150008E5 -:103D200085150008911500087D1500086915000823 -:103D300055150008A515000800000000010000004E -:103D40000000000063300000443D0008A02602206F -:103D5000B02802204172647550696C6F740025426E -:103D60004F415244252D424C002553455249414C68 -:103D70002500000002000000000000008D17000870 -:103D8000F917000840004000603102207031022025 -:103D9000020000000000000003000000000000001E -:103DA0003D180008000000001000000080310220D3 -:103DB0000000000001000000000000002834022084 -:103DC000010102000123000811220008AD220008B1 -:103DD0009122000843000000DC3D00080902430076 -:103DE000020100C0320904000001020201000524A2 -:103DF000001001052401000104240202052406002C -:103E000001070582030800FF09040100020A0000FF -:103E10000007050102400000070581024000000084 -:103E200012000000283E00081201100102000040AC -:103E300009124157000201020301000004030904B2 -:103E400025424F41524425004D6174656B4637361B -:103E5000352D53452D626473686F740030313233F1 -:103E60003435363738394142434445460000000076 -:103E70000080000000800000008000000080000042 -:103E80000000020000000400000004000000040024 -:103E90000000040000000400000004000000040012 -:103EA0000000000091190008491C0008F51C0008DA -:103EB00040004000A0340220A03402200100000095 -:103EC000B034022080000000400100000500000026 -:103ED0006D61696E0069646C650000000000802AF5 -:103EE00000000000AAAAAAAA00000024FFFF000008 -:103EF0000000000000A00A00000000010000000017 -:103F0000AAAAAAAA00000001FFFF0000000000000A -:103F1000000000000001000000000000AAAAAAAAF8 -:103F200000010000FFFF0000000000000000000092 -:103F30000040100000000000AAAAAAAA0040000049 -:103F4000FFFB0000000000000000000000814200B4 -:103F500000000000AAAAAAAA00404100EFFF00004A -:103F600000000080080000000000000000000000C9 -:103F7000AAAAAAAA00000000FFFF0000000000009B -:103F8000000000000000000000000000AAAAAAAA89 -:103F900000000000FFFF0000000000000000000023 -:103FA0000000000000000000AAAAAAAA0000000069 -:103FB000FFFF000000000000000000000000000003 -:103FC00000000000AAAAAAAA00000000FFFF00004B -:103FD00000000000000000000000000000000000E1 -:103FE00000000000000000000000000000000000D1 -:103FF00000000000000000000000000000000000C1 -:1040000000000000000000000000000000000000B0 -:104010008F0000000000000000801E000000000073 -:10402000FF000000B8280220D82302200000000072 -:10403000A43C000849040000B13C00085104000001 -:10404000BF3C000800960000000008009600000039 -:1040500000080000040000003C3E000800000000D2 -:104060000000000000000000000000000000000050 -:04407000000000004C -:00000001FF diff --git a/Tools/bootloaders/MatekG474-DShot_bl.bin b/Tools/bootloaders/MatekG474-DShot_bl.bin new file mode 100755 index 0000000000000..84d30793a3958 Binary files /dev/null and b/Tools/bootloaders/MatekG474-DShot_bl.bin differ diff --git a/Tools/bootloaders/MatekG474-DShot_bl.hex b/Tools/bootloaders/MatekG474-DShot_bl.hex new file mode 100644 index 0000000000000..1672d3204c12d --- /dev/null +++ b/Tools/bootloaders/MatekG474-DShot_bl.hex @@ -0,0 +1,1197 @@ +:020000040800F2 +:1000000000070020F101000845270008FD26000830 +:1000100025270008FD2600081D270008F301000819 +:10002000F3010008F3010008F3010008313700086C +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008253A00084D3A0008B2 +:10006000753A00089D3A0008C53A0008F3010008F7 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F3010008AD260008C1260008ED3A00086B +:1000A000F3010008F3010008F3010008F301000860 +:1000B000C13B0008F3010008F3010008F301000848 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000513B0008F3010008F3010008F301000888 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008D5260008E92600084D +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000990F00080000000000000000000000005F +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F052F912 +:1002600004F032FA4FF055301F491B4A91423CBF0F +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F030F904F052FACD +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F018B9000700200023002040 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000004A000800230020A4230020A823002097 +:1003000004660020E0010008E4010008E4010008A0 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F080FDFEE703F067 +:1003400009FD00DFFEE70000F8B500F03BFE04F019 +:100350007BF8074604F0CCF80546C0BB294B9F420A +:1003600035D001339F4235D0274B27F0FF029A4208 +:1003700033D1F8B200F058FC2E4642F2107400F06F +:1003800059FC08B10024264601F00EF948B30320B9 +:1003900000F03EF80024264635B11C4B9F4203D0A6 +:1003A00004F09EF800242646002004F057F80EB111 +:1003B00000F044F800F070FC02F0CCF90546C4B936 +:1003C00000F0BEFC4FF47A7003F03EFDF7E72E46D6 +:1003D0000024D4E704460126D1E7064640F6C414BB +:1003E000CDE740F6C4139C4204BF4FF47A74012653 +:1003F000D2E702F0AFF9431BA342E1D900F01EF8A7 +:10040000DAE700BF010007B0000008B0263A09B0E3 +:10041000084B187003280CD8DFE800F00805020824 +:10042000022000F02DBE022000F020BE024B002270 +:100430005A607047A8230020AC23002010B501F0BB +:10044000B3F830B1234B03221A70234B00225A60B9 +:1004500010BD224B224A1C4619680131F8D00433E2 +:100460009342F9D16268A242F2D31E4B9B6803F11A +:10047000006303F510439A42EAD204F003F804F053 +:1004800015F8002000F0B8FD0220FFF7C1FF164B61 +:100490009A6D00229A65996F9A67996FD96DDA659E +:1004A000D96FDA67D96F196E1A66D3F88010C3F85E +:1004B0008020D3F8803072B64FF0E0233021C3F8AB +:1004C000084DD4E9003281F311889D4683F30888F2 +:1004D0001047BDE7A8230020AC23002000900008AF +:1004E000209000080023002000100240094A1368F1 +:1004F00049F2690099B21B0C00FB01331360064BF3 +:10050000186844F2506182B2000C01FB02001860CE +:1005100080B27047142300201023002010B5002162 +:100520001022044600F0C8FD034B03CB206061603D +:100530001868A06010BD00BF9075FF1F2DE9F04145 +:10054000ADF5507D0DF13C086EAC40F275120746DA +:100550000D4610A80021C8F8001000F0ADFD4FF4C2 +:10056000C4720021204600F0A7FD02F0F3F8274BEB +:100570004FF47A72B0FBF2F0186093E807000223A0 +:1005800084E807000DF5ED702382FFF7C7FF49F2FD +:1005900004231F49238407A804F044F91D2384F889 +:1005A00032310DF2EB2207AB0DF1340C1E4603CEB7 +:1005B000664510605160334602F10802F6D130689A +:1005C00010603379137141460122204600F0C0FDCE +:1005D00000230393AB7E029305F11903019380B2CC +:1005E0000123CDE904800093E97E06A3D3E900232B +:1005F000384602F06DFC0DF5507DBDE8F08100BF7E +:10060000AFF300809E6AC421818A46EEB4230020A5 +:10061000344800082DE9F0412C4C237ADAB08046AA +:100620000D465BBB27A9284600F0B4FE074600280C +:1006300042D19DF89D60C82E3ED801464FF4A66277 +:10064000204600F039FD4FF48073C4F8F8314FF4C0 +:100650000073C4F80C334FF44073C4F820343246AE +:100660000DF19E0104F1090000F014FD26449DF8EF +:100670009C30777223720BB9EB7E237281220021AA +:1006800006AC27A800F018FD0122214627A800F09B +:10069000C7FE00230393AB7E029305F1190380B2DA +:1006A00001932823CDE904400093E97E05A3D3E913 +:1006B0000023404602F00CFC5AB0BDE8F08100BFB8 +:1006C000AFF3008026417272DF25D7B7805D00202E +:1006D000F0B5254E4FF48A7505FB0065F1B096F82C +:1006E000D83085F8DC300024D822214685F8E8404F +:1006F0003AA800F0E1FC06F1090000F0D5FCD5F8BD +:10070000E4308DF8F000C2B206AF06F109010DF138 +:10071000F100CDE93A3400F0BDFC394601223AA897 +:1007200000F0B4FE80B2CDE9047008230127CDE9C2 +:10073000023706F1D803019330230093317A0B4836 +:1007400007A3D3E9002302F0C3FBA04206DD02F0B9 +:1007500001F8C5F8E000384671B0F0BD2046FBE76F +:1007600078F6339F93CACD8D805D0020CC33002076 +:100770002DE9F04F264FDFF8A480264E87B038468B +:1007800002F0D2FB034600283AD00024CDE903440E +:10079000ADF81440027B8DF81420996840680294EB +:1007A00003AA03C21B681C4D43F000430293A146F9 +:1007B000A2462B68D3F810B001F0CEFF10EB080270 +:1007C00041F100032846CDF800A002A9D84704F55E +:1007D000A6640028C8BF49F00109B4F5266F05F5E5 +:1007E000A655E6D1B9F1000F05D0384602F0A0FBBE +:1007F00086F800A0C3E73378072B04D801333370A1 +:1008000007B0BDE8F08F024802F092FBF8E700BFA6 +:10081000CC330020B56200200034002040420F009D +:1008200070B50D4614461E4602F0AEFA50B9022EBF +:1008300010D1012C0ED112A3D3E90023C5E9002366 +:10084000012007E0282C10D005D8012C09D0052C58 +:100850000FD0002070BD302CFBD10BA3D3E90023B7 +:10086000ECE70BA3D3E90023E8E70BA3D3E90023CC +:10087000E4E70BA3D3E90023E0E700BFAFF3008078 +:10088000401DA12026812A0B78F6339F93CACD8D77 +:100890009E6AC421818A46EE26417272DF25D7B74F +:1008A000F017304A39059E5638B505460E4C0021E2 +:1008B000013500F0C3FBA4F82C55B4F82C0500F06A +:1008C000A5FB78B1B4F82C0500F0B0FB014648B99F +:1008D000B4F82C0500F0B2FBB4F82C350133A4F8C1 +:1008E0002C35EAE738BD00BF805D0020F8B50D4C1F +:1008F0000D4F0226A4F5805343F8307C237E3BB98C +:1009000065692DB1284600F0CDFE284603F040FF72 +:10091000204600F0C7FE012EA4F5A65400D1F8BD74 +:100920000126E7E7F0580020944800082DE9F04F31 +:100930008FB000AF05460C4602F026FA002849D1D8 +:10094000237E022B1BD1E38A012B18D101F002FF79 +:100950000646FFF7CBFD03464FF4C870DFF8C482AC +:10096000B3FBF0F206F5167602FB103316FA83F3AA +:10097000C8F80030E37E33B9A34B00221A703C372D +:10098000BD46BDE8F08F07F12401204600F0B6FC1B +:100990000028F4D107F11400FFF7C0FD97F82640B6 +:1009A00007F11401224607F1270003F009FF002890 +:1009B000E2D10F2C08D8944B1C70D8F80030A3F566 +:1009C0001673C8F80030DAE797F82410284602F0CA +:1009D000D3F9D4E7E38A282B2BD010D8012B23D0CE +:1009E000052BCCD1BFF34F8F8849894BCA6802F4DD +:1009F000E0621343CB60BFF34F8F00BFFDE7302BA6 +:100A0000BDD1844EE17E327A9142B8D1607E3146CA +:100A1000002291F8DC50854200F0A5800132042AC2 +:100A200001F58A71F5D1AAE721462846FFF786FD30 +:100A3000A5E721462846FFF7EDFDA0E7B2F8EC5008 +:100A40007B6005F103094FEA99094FEA8902D11D3C +:100A5000C908A8EBC1039D46EB460021584600F0AB +:100A60002BFB04F1EE012A463144584600F012FBFC +:100A70007B6813B9012000F0BFFA96F8D20000F0AD +:100A8000C5FA044630B9307200F0E0FA204600F0B2 +:100A9000B3FAB1E0D6F8D4203AB996F8D200B6F855 +:100AA0002C25824201D8FFF7FFFED6F8D4202A4435 +:100AB000944208D296F8D200B6F82C250130824232 +:100AC00001D8FFF7F1FE70685FFA89F2594600F02D +:100AD000FBFA08B9C54679E0726896F8D2002A4454 +:100AE0007260D6F8D42005EB0209C6F8D49000F065 +:100AF0008DFA814509D396F8D220D6F8D400013278 +:100B0000001B86F8D220C6F8D400FF2D0FD8002491 +:100B1000347200F09BFA204600F06EFA00F044FDBB +:100B20003D4B188108B9FFF789FCC54627E7BB682C +:100B300096F8D9000AFB0362FB68D2F8E41082F849 +:100B4000E83001F58061C2F8E030C2F8E410FFF748 +:100B5000BFFDFFF70DFE96F8D920013202F0030227 +:100B600086F8D920B6E74FF48A7A0AFB02F505F138 +:100B7000EA013144204600F0BBFCF86000287FF415 +:100B8000FEAE3544012285F8E82001F0E3FDD5F8FA +:100B9000E020D6ED007ADFED216A801A192838BFEF +:100BA000192040F6B832904228BF1046B8EE677A56 +:100BB00007EE900AF8EEE77A67EEA67ADFED186A9C +:100BC000E7EE267AFCEEE77AC6ED007A96F8D930A1 +:100BD000BB60BA6873680AFB02F4321992F8E81035 +:100BE00059B1D2F8E4108B42E8463FF427AF002118 +:100BF00082F8E810C2F8E010C5467368064A9B0AFE +:100C000001331381BBE600BFC533002000ED00E0D7 +:100C10000400FA05805D0020B4230020CDCCCC3D3B +:100C20006666663FC8330020014B1870704700BFEE +:100C3000C023002038B54FF00054134B22689A426D +:100C400020D1124B627D12481A70237D03724FF43B +:100C50008073C0F8F8314FF40073C0F80C330025EE +:100C60004FF44073C0F820340A49C0F8E450C92258 +:100C7000093000F00FFAE0222946204600F01CFA65 +:100C8000012038BD0020FCE79AAD44C5C0230020F8 +:100C9000805D00201600002037B500F085FC1F4C59 +:100CA0001F4D2049288102236B71236801225B6854 +:100CB0002046984704F580531A49D3F8C0340122DE +:100CC0005B6804F5A650984700230193164B17491B +:100CD00000931748174B4FF4805202F025F8164B3B +:100CE000197811B1124802F047F801F033FD0446BB +:100CF000FFF7FCFB4FF4C873B0FBF3F202FB1303E6 +:100D000004F5167010FA83F00C4B186003F0F0FB3A +:100D100008B10F232B8103B030BD00BF0034002089 +:100D2000B423002040420F0021080008C423002003 +:100D3000CC3300202D090008C0230020C833002038 +:100D40002DE9F04F2DED028B002493B00DF12C080E +:100D50009FED818BDFF83C92FFF70AFD0A94ADF816 +:100D600034400B94C8F804400026814DDFF804B2EB +:100D7000374601238DF81C302B688DF81D408DED12 +:100D8000008B0DF11D02D3F808A007A90023284607 +:100D9000D0479DF81CA0BAF1000F24D0D9F8143028 +:100DA00083F40053C9F81430102200210EA800F07B +:100DB00083F92B6808AA5F690AA90DF11E0328466A +:100DC000B84798E803000FAB83E803009DF8343080 +:100DD0008DF844300A9B0E930EA9DDE9082358468E +:100DE00002F084FA574606F5A666B6F5266F05F5B5 +:100DF000A655BED1002FB7D15E4801F0C5FF00282F +:100E00003FD15D4E01F0A6FC3368984239D301F022 +:100E1000A1FC0546FFF76AFB4FF4C873B0FBF3F281 +:100E200002FB130305F5167010FA83F03060534E81 +:100E30008DF82870377817B901238DF82830C7F15D +:100E40001005EDB20EA8FFF769FB062D28BF062599 +:100E50000EAB2A46D9190DF1290000F01BF90AAB97 +:100E60000393182302930135454B0193EDB20123FF +:100E70000093404804953AA3D3E9002301F0CAFF48 +:100E8000347001F067FC3F4A3F4D1368C31AB3F555 +:100E90007A7F2FD3106001F05FFC02460B46354885 +:100EA00002F050F8334801F06FFF18B32B7A374E39 +:100EB000002B14BF03230223737101F04BFC0EAF10 +:100EC0004FF47A730122B0FBF3F0394630603046BC +:100ED00000F0ECF9182302932D4B019380B240F2FD +:100EE0005513CDE90370009322481FA3D3E90023D3 +:100EF00001F090FF2B7A93B101F02CFC00260746FD +:100F00004FF48A7895F8D900304400F0030008FBCC +:100F1000005393F8E82072B10136042EF2D1C820B4 +:100F200002F092FF2B7A002B7FF410AF13B0BDECD0 +:100F3000028BBDE8F08FD3F8E02042B12B68FA2B8A +:100F400038BFFA23BA1A0533B2EB430FE4D3FFF7E5 +:100F5000BFFB0028E0D1E2E7000000000000000035 +:100F6000401DA12026812A0BF1C6A7C1D068080F19 +:100F700000340020CC330020C8330020C5330020CB +:100F8000C4330020B0620020805D0020B423002024 +:100F9000B46200200008004810B5074C204600F05D +:100FA000B3FE04F5A65000F0AFFEBDE81040034AC2 +:100FB0000349002003F0E6BB00340020F462002067 +:100FC000ED08000870B503F0DBF8094E094D3080DC +:100FD000002428683388834208D903F0CDF82B68B1 +:100FE00004440133B4F5104F2B60F2D370BD00BF41 +:100FF000E4620020B862002003F07CB900F10060D8 +:10100000920000F5104003F0FFB80000054B1A688D +:10101000054B1B889B1A834202D9104403F0ACB8DD +:1010200000207047B8620020E4620020024B1B6879 +:10103000184403F0A9B800BFB8620020024B1B6837 +:10104000184403F0B3B800BFB8620020064991F815 +:10105000243033B10023086A81F824300822FFF7D6 +:10106000CDBF0120704700BFBC620020022802BF34 +:10107000024B4FF000529A61704700BF00080048D1 +:10108000022802BF024B4FF400529A61704700BF22 +:101090000008004810B50023934203D0CC5CC45430 +:1010A0000133F9E710BD000003460246D01A12F9D9 +:1010B000011B0029FAD1704702440346934202D033 +:1010C00003F8011BFAE770472DE9F8431F4D14465A +:1010D00095F824200746884652BBDFF870909CB3F1 +:1010E00095F824302BB92022FF2148462F62FFF7C4 +:1010F000E3FF95F82400C0F10802A24228BF22466F +:10110000D6B24146920005EB8000FFF7C3FF95F889 +:101110002430A41B1E44F6B2082E17449044E4B2B7 +:1011200085F82460DBD1FFF791FF0028D7D108E0D4 +:101130002B6A03EB82038342CFD0FFF787FF00289F +:10114000CBD10020BDE8F8830120FBE7BC62002082 +:101150002DE9F8430D46044600219046284640F20A +:101160007912FFF7A9FF234620220021284602F02A +:101170005FF8231D02222021284602F059F8631D42 +:1011800003222221284602F053F8A31D0322252121 +:10119000284602F04DF804F10803102228212846C1 +:1011A00002F046F804F1100308223821284602F024 +:1011B0003FF804F1110308224021284602F038F8D4 +:1011C00004F1120308224821284602F031F804F104 +:1011D000140320225021284602F02AF804F11803B3 +:1011E00040227021284602F023F804F1200308224F +:1011F000B021284602F01CF804F121030822B8218E +:10120000284602F015F804F12207C0263B46314675 +:1012100008222846083602F00BF8B6F5A07F07F141 +:101220000107F3D1314604F132030822284601F0C8 +:10123000FFFF94F83260002704F13309F900BE4241 +:1012400001F5A4711FD8F70007F5A476B8F1000FD7 +:1012500008D1314604F599730722284601F0E8FFCA +:1012600007F24F1694F83201502828BF5020074645 +:1012700004EB0009B046A1450DD106EBC7000730CD +:10128000C008BDE8F88309EB07030822284601F0EF +:10129000CFFF0137D2E704F2331341460822284634 +:1012A00001F0C6FF08F108080134E4E713B504466D +:1012B0000846002101602346C0F803102022019057 +:1012C00001F0B6FF0198231D0222202101F0B0FF9A +:1012D0000198631D0322222101F0AAFF0198A31D9A +:1012E0000322252101F0A4FF019804F10803102234 +:1012F000282101F09DFF072002B010BDF7B5047F43 +:1013000005460E462CB1838A122B02D9012003B068 +:10131000F0BD0023194607220096284601F04CFE36 +:10132000731C0093012200230721284601F044FE8C +:10133000D4B9B31C0093052223460821284601F0A6 +:101340003BFE0D24B378102BE0D83746B278BB1B98 +:10135000934210D32B7FA88A0734E408B3B98442A0 +:1013600094BF00200120D2E7AB8ADB00083BDB08FA +:10137000B3700824E6E7FB1C0093214600230822F3 +:10138000284601F019FE08340137DFE7201A18BF9C +:101390000120BCE7F7B5047F05460E462CB1838AD1 +:1013A000CA2B02D9012003B0F0BD002319460096D4 +:1013B0000822284601F000FE731CD4B908220093CD +:1013C00011462346284601F0F7FD10247378C82BF8 +:1013D000E8D8012372785F1C013B934210D32B7F26 +:1013E000A88A0734E408B3B9844294BF00200120DE +:1013F000D9E7AB8ADB00083BDB0873700824E5E71C +:10140000F3190093214600230822284601F0D4FD59 +:1014100008343B46DEE7201A18BF0120C3E700006E +:101420002DE9F8430D460446164600218122284640 +:10143000FFF742FE234608220021284601F0F8FE6D +:10144000C6B9631C07220821284601F0F1FE0F26C9 +:1014500094F901306778002BB8BF7F2704EB0709A8 +:10146000B0464C4508D10736082010FB0760C0087D +:10147000BDE8F8830826EBE7A31C4146082228466E +:1014800001F0D6FE08F108080134EAE72DE9F04141 +:101490000D46044616460021CE222846FFF70CFED4 +:1014A000234628220021284601F0C2FEBEB904F1DD +:1014B000080308222821284601F0BAFE302614F835 +:1014C000080FC82828BFC82080460027B84506EB6B +:1014D000C70106D806EBC800C008BDE8F081282681 +:1014E000EDE70137E3190822284601F0A1FEEDE7F8 +:1014F000F7B5047F05460E4634B1838AB3F5827F83 +:1015000002D9012003B0F0BD009601231022002172 +:10151000284601F051FDDCB9B31C00930922234693 +:101520001021284601F048FD19247388B3F5807F07 +:10153000E7D837467288BB1B934210D32B7FA88A0B +:101540000734E408B3B9844294BF00200120D9E7EE +:10155000AB8ADB00103BDB0873801024E5E73B1D02 +:101560000093214600230822284601F025FD083477 +:101570000137DFE7201A18BF0120C3E730B5094D56 +:101580000A4491420DD011F8013B5840082340F322 +:101590000004013B2C4013F0FF0384EA5000F6D115 +:1015A000EFE730BD2083B8EDF7B5384A10685168D1 +:1015B0006B4603C36A4636493648082303F010F9E0 +:1015C0000446002833D10A25334A106851686B4617 +:1015D00003C36A4631492F48082303F001F9044642 +:1015E000002849D00369B3F5EE2F45D8B0F866104E +:1015F00040F2924291423FD1294A024402F15C01F9 +:101600008B4239D35C3B234900209E1AFFF7B6FF7B +:101610003246074604F164010020FFF7AFFFA368DC +:101620009F4229D1E368984208BF002524E003695E +:10163000B3F5EE2F27D8418B40F29242914220D150 +:10164000174A024402F110018B4218D3103B114992 +:1016500000209D1AFFF792FF2A46064604F1180162 +:101660000020FFF78BFFA3689E4202D1E3689842F7 +:1016700001D00D25A8E70025284603B0F0BD1025B0 +:10168000A2E70C25A0E70B259EE700BF5448000801 +:10169000DC6F0700009000085D480008906F0700AD +:1016A0000870FFF710B5037C044613B9006803F017 +:1016B0007FF8204610BD00000023BFF35B8FC3609E +:1016C000BFF35B8FBFF35B8F8360BFF35B8F7047AC +:1016D000BFF35B8F0068BFF35B8F704770B5054643 +:1016E0000C30FFF7F5FF05F1080604463046FFF71A +:1016F000EFFFA04206D930466D68FFF7E9FF2544A9 +:10170000281A70BD3046FFF7E3FF201AF9E7000002 +:1017100070B50546406898B105F10800FFF7D8FF9D +:1017200005F10C0604463046FFF7D2FF84423046EE +:1017300094BF6D680025FFF7CBFF013C2C44201AB5 +:1017400070BD000038B50C460546FFF7C7FFA04244 +:1017500010D305F10800FFF7BBFF04446868B4FB31 +:10176000F0F100FB1144BFF35B8F0120AC60BFF3CD +:101770005B8F38BD0020FCE72DE9F0411446074699 +:101780000D46FFF7C5FF844228BF0446D4B1B846D2 +:1017900058F80C6B4046FFF79BFF304428604046EA +:1017A0007E68FFF795FF331A9C4203D86C600120D6 +:1017B000BDE8F0816B60A41B3B68AB602044E8602F +:1017C0000220F5E72046F3E738B50C460546FFF75B +:1017D0009FFFA04210D305F10C00FFF779FF0444EE +:1017E0006868B4FBF0F100FB1144BFF35B8F01208C +:1017F000EC60BFF35B8F38BD0020FCE72DE9FF41B3 +:10180000884669460746FFF7B7FF6C4606B204EB09 +:10181000C6060025B44209D06268206808EB0501BD +:10182000FFF738FC636808341D44F3E7294638465F +:10183000FFF7CAFF284604B0BDE8F081F8B50546B9 +:101840000C300F46FFF744FF05F10806044630460A +:10185000FFF73EFFA042304688BF6C68FFF738FFB5 +:10186000201A386020B130462C68FFF731FF204441 +:10187000F8BD000073B5144606460D46FFF72EFF6F +:10188000844228BF04460190DCB101A93046FFF72D +:10189000D5FF019B33B93268C5E90233C5E900249D +:1018A00001200CE09C4238BF0194286001986860D8 +:1018B0008442F5D93368AB60241AEC60022002B090 +:1018C00070BD2046FBE700002DE9FF410F46694649 +:1018D000FFF7D0FF6C4600B204EBC0050026AC4217 +:1018E00009D0D4F8048054F8081BB8194246FFF711 +:1018F000D1FB4644F3E7304604B0BDE8F081000078 +:1019000038B50546FFF7E0FF044601462846FFF7D5 +:1019100019FF204638BD00007047000010B4134680 +:10192000026814680022A4465DF8044B604700007A +:1019300000F5805090F859047047000000F5805081 +:1019400090F852047047000000F5805090F9580458 +:101950007047000050207047302383F3118800F552 +:101960008052D2F89C34D2F898041844D2F89434B7 +:101970001844D2F87C341844D2F88C341844D2F885 +:1019800088341844002383F31188704700F5805091 +:10199000C0F854140120704738B5C26A936923F027 +:1019A00001039361044600F0D5FE0546E36A9B6996 +:1019B000DB0706D500F0CEFE431BFA2BF6D900203C +:1019C00004E004F58054012084F8520438BD00007E +:1019D0002DE9F04F0C4600F5805185B01F4691F877 +:1019E0005234BDF83890054690469BB1D1F8783412 +:1019F0000133C1F878342368980006D4237B082B80 +:101A00000BD9627B0AB10F2B07D9D1F87C34013393 +:101A1000C1F87C344FF0FF3010E0302383F311889D +:101A2000EB6AD3F8C42012F4001B0AD0D1F880343A +:101A30000133C1F88034002080F3118805B0BDE87F +:101A4000F08FD3F8C4302068C3F3014A6B6A482290 +:101A5000002812FB0A33B4BF40F0804080041860B5 +:101A60002268520044BF40F000501860207B4FEACB +:101A70000A6242EA00425A60607B4FEA4A1610B39B +:101A800042F440125A60D1F8B0240132C1F8B024B7 +:101A9000AA1902F58352117B41F020011173207BBA +:101AA000039300F0B3FE039B033080105FFA8BF2C8 +:101AB00082420BF1010B0DDA04EB820103EB82028F +:101AC00049689160F2E7AA1902F58352117B60F32D +:101AD0004511E3E7EB6A012202FA0AF2C3F8CC20CF +:101AE00005EB4A11AB1903F5825301F58251C3E9A5 +:101AF00004871831234604F10C0253F8040B41F813 +:101B0000040B9342F9D11B880B802E4441F26803E9 +:101B100046F803A006F5805609F0030396F86C20FA +:101B200043F0100322F01F02134386F86C300023A9 +:101B300083F31188CDF8009042463B462146284663 +:101B400000F02AFE012079E713B500F580540191D9 +:101B5000606CFFF7DDFD1F280AD90199606C202217 +:101B6000FFF74CFEA0F120035842584102B010BDCF +:101B70000020FBE708B5302383F3118800F580507F +:101B8000406CFFF799FD002383F3118808BD000026 +:101B900000220260828142608260704710B500229C +:101BA0000023C0E900230023044603810C30FFF723 +:101BB000EFFF204610BD00002DE9F0479A4688B09F +:101BC000074688469146302383F3118807F58054F1 +:101BD0006846FFF7E3FF606CFFF780FD1F282DD9F3 +:101BE000606C20226946FFF78BFE202826D194F8EE +:101BF00052341BB303AD444605AB2E4603CE9E4282 +:101C000020606160354604F10804F6D13068206038 +:101C1000B388A380DDE90023C9E90023BDF80830BB +:101C2000AAF80030002383F3118853464A46414600 +:101C3000384608B0BDE8F04700F09CBD002080F3B6 +:101C4000118808B0BDE8F0872DE9F84F002306465B +:101C5000C0E90133294B46F8303B00F58154054675 +:101C600088463746103438462037FFF797FFA7429B +:101C7000F9D105F580544FF4805326630026C4E95A +:101C80000D366764012305F5835705F5A359E6630F +:101C900084F8403084F84830103709F110094FF0CB +:101CA000000A4FF0000B47E908ABA7F11800FFF757 +:101CB0006FFF203747F8286C4F45F4D1B8F1010F7A +:101CC00084F85884A4F85A64A4F85C64A4F85E64A8 +:101CD00084F86064A4F86264A4F86464A4F8666498 +:101CE00084F8686402D9064800F02EFD054B53F8CD +:101CF0002830EB622846BDE8F88F00BF9448000802 +:101D0000684800088448000810B5044B1978044658 +:101D10004A1C1A70FFF798FF204610BDF1620020A0 +:101D20002DE9F84315460C4600295CD0022001F04D +:101D300073FE2E49B0FBF4F78C428CBF0A211121AF +:101D40004B1EB7FBF1F601FB1671DAB221B1022B83 +:101D50001946F5D8002032E0731EB3F5806FF9D232 +:101D6000C2EBC20808F103014FEAE10EC1F3C7015B +:101D7000A2EB010C0EF101094FF47A735FFA8CF7B4 +:101D80000EFB033E59FA8CFCBEFBFCFCBCF5617FEC +:101D900017DC1FFA8CF34A1C57FA82F27243B0FB2D +:101DA000F2F08442D6D14A1E0F2AD3D87A1E072ACF +:101DB000D0D801202B806E8028716971AF71BDE889 +:101DC000F88308F1FF314FEAE10CC1F3C701521A61 +:101DD0000CF1010ED7B20CFB03335EFA82F2B3FBB7 +:101DE000F2F39BB2D7E70846E9E700BF3F420F0096 +:101DF00030B50D4B0D4D05201C786C438C420ED137 +:101E00005978518099785171D978917119791171F6 +:101E10005B7903EB83035B001380012030BD013845 +:101E200003F10603E8D1F9E7D448000840420F0067 +:101E300038B500F58053114A93F85834D55C4FF407 +:101E40005472554305F1804303F5244304460021B1 +:101E50001846FFF731F90A4B60612B44A361094B27 +:101E60002B44E361084B2B442362084B2B446362F1 +:101E7000E36A0022C3F8C02038BD00BF7C480008D8 +:101E800070A40040B0A4004088A5004078A600409F +:101E90002DE9F04F00F580551F4695F85834022B78 +:101EA00089B004468946904604D90026304609B0D8 +:101EB000BDE8F08FA64A52F8231009B942F8230072 +:101EC000A448C4F80C900178277499B9302383F39F +:101ED0001188A14B9A6D42F000729A659A6B42F09C +:101EE00000729A639A6B22F000729A630123037066 +:101EF00081F3118895F85134CBB9302383F31188DD +:101F0000964A95F85834D35C012B2AD0022B2FD057 +:101F10003BB90321152001F093FE0321162001F0A7 +:101F20008FFE012385F85134002383F31188302379 +:101F300083F31188E26A936923F01003936100F040 +:101F400009FC8246E36A9E6916F0080617D000F085 +:101F500001FCA0EB0A03FA2BF4D9002686F31188C2 +:101F6000A4E70321562001F06BFE03215720D6E79A +:101F70000321582001F064FE03215920CFE79A691C +:101F800042F001029A6100F0E5FB8246E36A9A6939 +:101F9000D00706D400F0DEFBA0EB0A03FA2BF5D93C +:101FA000DBE79A6942F002029A61E36A4FF0000AA5 +:101FB000C3F854A08AF31188686CFFF77DFB04F521 +:101FC000825B0BF1100B202200216846FFF774F8AA +:101FD00002A8FFF7DDFDCDF818A06A460BEB06035B +:101FE0000DF1180E9446BCE80300F44518605960E2 +:101FF000624603F10803F5D1DCF8000018602036D2 +:102000009CF804201A71B6F5806FDCD1002304F52A +:10201000A25285F8503485F853341A324946204686 +:10202000FFF77EFE064690B9E26A936923F001034A +:10203000936100F08FFB0546E36A9B69D9077FF542 +:1020400034AF00F087FB431BFA2BF5D92DE795F849 +:102050005E34C5F86C94591E95F85F34E26A013B12 +:102060001B0243EA416395F8601401390B43B5F84C +:102070005C14013943EA0143D361B8F1000F36D053 +:1020800004F5A352023241462046FFF7B1FE90B953 +:10209000E26A936923F00103936100F05BFB05465C +:1020A000E36A9B69DA077FF500AF00F053FB431B3F +:1020B000FA2BF5D9F9E695F86724C5F87084511E16 +:1020C00095F86824E36A013A120142EA012295F880 +:1020D000661401390A43B5F86414013942EA014231 +:1020E00042F40002DA60E36A4FF420629A64204608 +:1020F000FFF79EFE002385F85934E36A6FF04042F3 +:102100001A65E36A164A5A65E36A44229A65E36AE5 +:102110000722C3F8DC20E36A03229742DA653FF422 +:10212000C5AEE26A936923F00103936100F012FBEC +:102130000746E36A9B69DB0705D500F00BFBC31B71 +:10214000FA2BF6D9B1E6012385F85234AEE600BF8A +:10215000E8620020F0620020001002407C48000885 +:102160009B0008002DE9F04F054689B0904699463E +:10217000002741F2680A00F58056EB6AD3F8D430A4 +:10218000FB40D80751D505EB471252444FEA471B95 +:102190001379190749D4D6F884340133C6F8843446 +:1021A00005F5A553C3E9008913799A0648BFD6F807 +:1021B000B43405EB0B0248BF0133524448BFC6F8A4 +:1021C000B434137943F008031371DB0722D596F872 +:1021D0005334FBB105F58254183468465C44FFF76C +:1021E000DDFC03AB04F1080C206861681A4603C2E9 +:1021F000083464451346F7D120681060A2889A809D +:102200000123ADF808302B68CDE90089DB6B694606 +:1022100028469847D6F8A834D6F854040133C6F8AF +:10222000A83410B103681B6998470137202FA4D147 +:1022300009B0BDE8F08F00002DE9F04F8DB00446E5 +:102240000F4600F089FA82468946002F56D1E36A8C +:10225000D3F89020920141BF04F58051D1F8982421 +:102260000132C1F89824D3F89020160703D100203A +:102270000DB0BDE8F08FD3F89050E669C5F30125A5 +:10228000482303FB0566E8464046FFF781FC3268B9 +:1022900051004ABF22F06043C2F38A4343F0004337 +:1022A000920048BF43F080430093736813F4001317 +:1022B0001FBF04F5805201238DF80D30D2F8B834D9 +:1022C0000EBF8DF80D300133C2F8B834F38803F037 +:1022D0000F038DF80C304FF0000B9DF80C0000F050 +:1022E00095FA5FFA8BF3984220D9F2180CA90B44A7 +:1022F000127A03F82C2C0BF1010BEEE7012FB6D16B +:10230000E36AD3F89820950141BF04F58051D1F8D4 +:1023100098240132C1F89824D3F898201007A6D049 +:10232000D3F89850266AC5F30125A9E7EFB9E36A07 +:10233000C3F8945004A8FFF731FC98E80F0007ADEC +:1023400007C52B800023ADF8183023682046CDE95F +:1023500004A9DB6B04A9984704F5805458B1D4F85C +:1023600090340133C4F8903482E7012F04BFE36A4C +:10237000C3F89C50DEE7D4F894340133C4F89434A5 +:10238000012075E72DE9F04105460F4600F5805420 +:10239000012639462846FFF74FFF10B184F85364F1 +:1023A000F7E7D4F8A834D4F854040133C4F8A834B7 +:1023B00020B10368BDE8F0411B691847BDE8F08112 +:1023C000F0B5C36A1A6C12F47F0F2BD000F580545D +:1023D0001B6CC4F8AC3441F26805002347194FF078 +:1023E000010C00EB43122A445E01117911F0020F37 +:1023F00015D0490713D4B959C66AD6F8C8E00CFA03 +:1024000001F111EA0E0F0AD0C6F8D010117941F08F +:1024100004011171D4F88C240132C4F88C240133E6 +:10242000202BDED1F0BD00002B4B70B51E561B5C7F +:10243000012B2FD8294D2A4A55F8233052F826402F +:102440000BB341B3236D1A060FD58023236500F02B +:1024500083F950EA01020B4602D0013861F1000312 +:10246000024655F82600FFF77DFE236D1B032CD591 +:1024700055F826304FF4002203F5805322650122DF +:1024800083F8592421E001232365082323654FF4B1 +:102490008063236570BD236DDA0702D4236D9B072B +:1024A00006D5032355F8260023650021FFF76AFFB0 +:1024B000236D180702D4236DD90606D5182355F8C5 +:1024C000260023650121FFF75DFF55F82600BDE8D2 +:1024D0007040FFF775BF00BF80480008E862002029 +:1024E0008448000808B5302383F31188FFF768FF9C +:1024F000002383F3118808BDC36AD3F8C40080F4B5 +:102500000010C0F34050704708B5302383F31188A2 +:1025100000F58050406CFFF7E1F8002383F3118849 +:1025200043090CBF0120002008BD000000F58053C6 +:1025300093F8592462B1C16A8A6922F001028A6162 +:10254000D3F89C240132C3F89C24002283F8592438 +:10255000704700002DE9F743302181F3118800F521 +:1025600082511031002541F2680E4FF0010800F54C +:10257000805C00EB45147444267977071CD4F6067A +:102580001AD5D0F82C908E69D9F8C87008FA06F6DA +:102590003E4211D04F6801970F689742019F9F41BB +:1025A0000AD2C9F8D060267946F004062671DCF814 +:1025B00088440134CCF888440135202D01F12001F4 +:1025C000D7D1002383F3118803B0BDE8F083000066 +:1025D000F8B51E46002313700F4605461446FFF754 +:1025E00093FF80F0010038701EB12846FFF784FF8A +:1025F0002070F8BD2DE9F04F85B09946DDE90EA3B6 +:102600000D4602931378019391F800B08046164668 +:1026100000F0A2F82B7804460F4613B93378002B4C +:1026200041D022463B464046FFF794FFFFF75AFF52 +:10263000FFF77CFF4B4632462946FFF7C9FF2B7850 +:1026400033B1BBF1000F03D0012005B0BDE8F08F1E +:10265000337813B1019B002BF6D108F58053039317 +:10266000029B544577EB03031DD2039BD3F854041C +:10267000C8B10368AAEB04011B6898474B46324671 +:1026800029464046FFF7A4FF2B7813B1BBF1000F9A +:10269000DAD1337813B1019B002BD5D100F05CF86F +:1026A00004460F46DCE70020CFE7000008B5002114 +:1026B0000846FFF7B9FEBDE8084001F06DB800001C +:1026C00008B501210020FFF7AFFEBDE8084001F08A +:1026D00063B8000008B500210120FFF7A5FEBDE8A2 +:1026E000084001F059B8000008B501210846FFF77D +:1026F0009BFEBDE8084001F04FB8000000B59BB05C +:10270000EFF3098168226846FEF7C4FCEFF3058306 +:10271000014B9B6BFEE700BF00ED00E008B5FFF743 +:10272000EDFF000000B59BB0EFF309816822684619 +:10273000FEF7B0FCEFF30583014B5B6BFEE700BFD8 +:1027400000ED00E0FEE700000FB408B5029801F0CC +:102750002BFBFEE701F014BE01F0F6BD13B56C468D +:1027600084E80600031D94E8030083E805000120C7 +:1027700002B010BD73B58568019155B11B885B0728 +:1027800007D4D0E900369B6B9847019AC1B2304616 +:10279000A847012002B070BDF0B5866889B0054633 +:1027A0000C465EB1BDF838305B070AD4D0E900377B +:1027B0009B6B98472246C1B23846B047012009B00A +:1027C000F0BD00220023CDE900230023ADF808303E +:1027D0000A4603AB01F10806106851681C4603C4A1 +:1027E0000832B2422346F7D1106820609288A28056 +:1027F000FFF7B2FF0423ADF808302B68CDE90001E4 +:10280000DB6B694628469847D8E70000082817D9A7 +:1028100009280CD00A280CD00B280CD00C280CD07E +:102820000D280CD00E2814BF4020302070470C20FB +:1028300070471020704714207047182070472020E0 +:10284000704700002DE9F041456A15B94162BDE8C5 +:10285000F0814B6823F06047C3F38A464FEAD37E8A +:10286000C3F3807816EA230638BF3E46AC462B46B3 +:102870005A68BEEBD27F22F060440AD0002A18DAF0 +:10288000A40CB44217D19D420FD10D60DEE7134670 +:10289000EEE7A74207D102F08044C2F380724245BE +:1028A0000BD054B1EFE708D2EDE7CCF800100B6085 +:1028B000CDE7B44201D0B442E5D81A689C46002A5C +:1028C000E5D11960C3E700002DE9F047089D01F04C +:1028D00007044FEAD508224405F0070500EBD100B4 +:1028E0004FF47F49944201D1BDE8F08704F0070717 +:1028F00005F0070A57453E4638BF5646C6F108065A +:10290000111B8E4228BF0E46E10808EBD50E415C34 +:1029100013F80EC0B94029FA06F721FA0AF1FFB2FE +:102920008CEA010147FA0AF739408CEA010C03F8F6 +:102930000EC034443544D5E780EA0120082341F233 +:10294000210201B24000002980B203F1FF33B8BF79 +:10295000504013F0FF03F4D17047000038B50C4627 +:102960008D18A54200D138BD14F8011BFFF7E4FF14 +:10297000F7E7000042684AB11368436043898189E0 +:1029800001339BB29942438138BF8381104670471F +:1029900070B588B0202204460D4668460021FEF737 +:1029A0008BFB20460495FFF7E5FF024658B16B46C6 +:1029B000054608AE1C4603CCB44228606960234635 +:1029C00005F10805F6D1104608B070BD082817D9E2 +:1029D00009280CD00A280CD00B280CD00C280CD0BD +:1029E0000D280CD00E2814BF4020302070470C203A +:1029F000704710207047142070471820704720201F +:102A000070470000082817D90C280CD910280CD9B9 +:102A100014280CD918280CD920280CD930288CBFA0 +:102A20000F200E207047092070470A2070470B20A6 +:102A300070470C2070470D20704700002DE9F843C7 +:102A4000078C072F04461ED9D0E9029800254FF6BF +:102A5000FF73C5F12006A5F1200029FA05F108FA57 +:102A600006F628FA00F031430143C9B21846FFF7D1 +:102A700063FF0835402D0346EBD1E1693A46BDE8D6 +:102A8000F843FFF76BBF4FF6FF70BDE8F883000017 +:102A900010B54B6823B9CA8A63F30902CA8210BD14 +:102AA00004691A681C600361C38A013BC3824A60DF +:102AB000EFE700002DE9F84F1D46CB8A0F46C3F320 +:102AC00009010529814692460B4630D00020AAB262 +:102AD00007F11A049EB2042E1FFA80F80FD8904511 +:102AE00003F1010306D3FB8A0A4462F30903FB8264 +:102AF00001201AE01AF80060E6540130EAE7904538 +:102B0000F1D2A1F1050B1C237C68BBFBF3F203FBA4 +:102B100012BB1FFA8BF6002C45D14846FFF72AFF5F +:102B2000044638B978606FF00200BDE8F88F4FF0C6 +:102B30000008E6E7002606607860ADB24FF0000BB3 +:102B4000454510D90AEB0803221D13F8011B9155C6 +:102B5000B1B208F101081B291FFA88F82BD04545AE +:102B600006F10106F1D8FB8AC3F30902154465F3A7 +:102B70000903BCE7013292B21C462368002BF9D14D +:102B80006B1F0B441C21B3FBF1F301339BB29A4240 +:102B9000D3D2BBF1000FD0D14846FFF7EBFE20B9EE +:102BA000C4F800B0BFE70122E7E7C0F800B05E4616 +:102BB00020600446C1E74545D5D94846FFF7DAFE0F +:102BC00008B92060AFE7C0F800B0002620600446D6 +:102BD000B6E700002DE9F04F2DED028B1C4683B0C7 +:102BE0005B69019207468846002B00F09A80238C8F +:102BF0002BB1E269002A00F09480072B35D807F149 +:102C00000C00FFF7B7FE054638B96FF002052846FD +:102C100003B0BDEC028BBDE8F08F14220021FEF75B +:102C20004BFA228CE16905F10800FEF733FA208C9B +:102C3000013080B2FFF7E6FEFFF7C8FE013880B230 +:102C40002084013028746369228C1B782A4403F0A5 +:102C50001F0363F03F0348F0004113723846696078 +:102C60002946FFF7EFFD0125D1E700F10C034FF0F6 +:102C7000000908EE103A4FF0800A4E464D4618EE15 +:102C8000100AFFF777FE83460028BED014220021E9 +:102C9000FEF712FA002E3AD1019BABF8083002225F +:102CA0000BF1080E1FFA82FC0CF10100BCF1060FBB +:102CB000218C80B201D88E422BD3FFF7A3FEFFF701 +:102CC00085FE62691278013802F01F028E4208BF49 +:102CD0004FF0400A42EA49121BFA80F14AEA020A1E +:102CE000013048F0004281F808A08BF81000CBF8C2 +:102CF000042059463846FFF7A5FD238C0135B34221 +:102D00002DB289F001094FF0000AB8D17FE7002207 +:102D1000C6E7E169895D0EF802100136B6B20132EC +:102D2000C0E76FF0010572E7F8B515460E46302290 +:102D3000002104461F46FEF7BFF9069B6360B5F508 +:102D4000001F079BA76034BF6A094FF6FF72A3629A +:102D500097B2E66104F1100000239A4206D80023DE +:102D60000360A782E3822383E360F8BD066001333A +:102D700030462036F1E7000003781BB94BB2002B38 +:102D8000C8BF01707047000000787047F8B50C4666 +:102D9000C969074611B9238C002B37D1257E1F2D19 +:102DA00034D8387828BB228C072A2CD8268A36F0CB +:102DB00003032BD14FF6FF70FFF7D0FD20F0010089 +:102DC0003102400441EA0561400C41EA40254FF6DA +:102DD000FF72234629463846FFF7FCFE002807DD30 +:102DE000626913780133DBB21F2B88BF0023137095 +:102DF000F8BD218A2D0645EA012505432046FFF747 +:102E00001DFE0246E5E76FF00300F1E76FF00100F9 +:102E1000EEE7000070B58AB004461646002128226D +:102E200068461D46FEF748F9BDF83830ADF8103059 +:102E30000F9B05939DF840308DF81830119B079338 +:102E40006946BDF84830ADF820302046CDE902652E +:102E5000FFF79CFF0AB070BD2DE9F041D36905462C +:102E60000C4616460BB9138C5BBB377E1F2F28D838 +:102E700095F80080B8F1000F26D03046FFF7DEFD50 +:102E80003378210241EAC33141EA0801338A41EA39 +:102E9000076141EA03410246334641F0800128467A +:102EA000FFF798FE00280ADD3378012B07D17269FD +:102EB00013780133DBB21F2B88BF00231370BDE8EA +:102EC000F0816FF00100FAE76FF00300F7E7000010 +:102ED000F0B58BB004460D461746002128226846FF +:102EE0001E46FEF7E9F89DF84C305A1E53425341F6 +:102EF0008DF800309DF84030ADF81030119B0593EF +:102F00009DF848308DF81830149B07936A46BDF839 +:102F10005430ADF8203029462046CDE90276FFF73F +:102F20009BFF0BB0F0BD0000406A00B10430704759 +:102F3000436A1A68426202691A600361C38A013BEC +:102F4000C38270472DE9F041D0F82080194E144615 +:102F50001D464146002709B9BDE8F081D1E90223A9 +:102F6000A21A65EB0303964277EB03031ED2036AB2 +:102F70008B420DD1FFF78CFD036A1B680362036966 +:102F80000B60C38A0161016A013BC3828846E2E7A4 +:102F9000FFF77EFD0B68C8F8003003690B60C38A39 +:102FA0000161013BC382D8F80010D4E78846096864 +:102FB000D1E700BF80841E002DE9F04F8BB00D4695 +:102FC000DDF8509014469B468046002800F0198199 +:102FD000B9F1000F00F01581531E3F2B00F2118153 +:102FE000012A03D1BBF1000F40F00B810023CDE992 +:102FF0000833B8F81430B5EBC30F4FEAC30703D357 +:1030000000200BB0BDE8F08F2B199F42D8F80C3090 +:103010003ABF7F1BFFB227461BB9D8F81030002BF0 +:103020007AD0272D4ED8C5F12806B7424FF00003BD +:103030002CBFF6B23E4600932946D8F8080008ABEC +:103040003246FFF741FCA7EB060A35445FFA8AFADD +:10305000B8F8143003F10053053BDB000493D8F8B3 +:103060000C3003932821039B13B1BAF1000F2CD12C +:10307000D8F8100040B1BAF1000F05D0009608ABA7 +:103080005246691AFFF720FC38B2002FB8D0660705 +:103090000AD00AAB03EBD401624211F8083C02F0FB +:1030A0000702134101F8083C082C3CD9102C40F2CF +:1030B000B580202C40F2B780BBF1000F00F09C805F +:1030C000082334E0BA460026C2E7049BE02B28BF61 +:1030D000E02306930B44AB42059314D95A1B039883 +:1030E0000096924534BF5246D2B2691A08AB0430FA +:1030F0000792FFF7E9FB079A1644AAEB020A154468 +:10310000F6B25FFA8AFA049B069A05999B1A049311 +:10311000039B1B680393A6E70093D8F8080008AB4D +:103120003A462946AEE7BBF1000F13D00123B4EBBA +:10313000C30F6CD0082C12D89DF82030621E23FAE1 +:1031400002F2D50706D54FF0FF3202FA04F423430A +:103150008DF820309DF8203089F8003051E7102C90 +:1031600012D8BDF82030621E23FA02F2D10706D52C +:103170004FF0FF3202FA04F42343ADF82030BDF8DB +:103180002030A9F800303CE7202C0FD80899631EA6 +:1031900021FA03F3DA0705D54FF0FF3202FA04F4FF +:1031A0000C430894089BC9F800302AE7402C2BD028 +:1031B000DDE90865611EC4F12102A4F1210326FAAC +:1031C00001F105FA02F225FA03F311431943CB0783 +:1031D00012D50122A4F12003C4F1200102FA03F365 +:1031E00022FA01F1A240524243EA010363EB430396 +:1031F00032432B43CDE90823DDE90823C9E9002345 +:10320000FFE66FF00100FCE66FF00800F9E6082C1D +:10321000A0D9102CB3D9202CEED8C3E7BBF1000FF6 +:10322000ADD0022383E7BBF1000FBBD004237EE7C0 +:1032300030B5012A144638BF0124402C85B028BF80 +:1032400040240025012ACDE9025518D81B788DF8B5 +:10325000083063070AD004AB03EBD405624215F8CB +:10326000083C02F00702934005F8083C0091034631 +:103270002246002102A8FFF727FB05B030BD082A2F +:10328000E4D9102A03D81B88ADF80830E1E7202ADA +:103290008DBFD3E900231B680293CDE90223D8E751 +:1032A00010B5CB681BB98B600B618B8210BD0469B4 +:1032B0001A681C600361C38A013BC382CA60F0E7DD +:1032C00003064CBFC0F3C0300220704708B5024669 +:1032D000FFF7F6FF022806D15306C2F30F2001D1F3 +:1032E00000F0030008BDC2F30740FBE72DE9F04FF3 +:1032F00093B0CDE903230A6804461046FFF7E0FFC8 +:10330000022814BFC2F306260026002A0D46824674 +:1033100080F2F78112F0C04940F0F381097B002967 +:1033200000F0EF81022803D02378B34240F0EC8113 +:10333000C2F304630693104602F07F030593FFF780 +:10334000C5FF059B29444FEA834848EA0A4848EAF2 +:103350004668CE7800230022CDE90823F30983468E +:1033600048EA0008029367D0059B0093024667680D +:10337000534608A92046B847002800F0C881276AAC +:103380004FB9414604F10C00FFF702FB074690B924 +:103390006FF0020054E03B6998450DD03F68002F64 +:1033A000F9D1414604F10C00FFF7F2FA0746002874 +:1033B000EED0236A3B60276297F817C006F01F081B +:1033C000CCF3840CACEB08001FFA80FE0028B8BFD9 +:1033D0000EF12000A8EB0C031FFA83FED7E90221AF +:1033E000B8BF00B2002B0793BEBF0EF120031BB283 +:1033F000079352EA010338D0039BDFF824E39A1ABB +:10340000049B4FF0000C63EB010196457CEB01033C +:103410002BD36B7B97F81AE0734519D1029B002BD5 +:1034200078D0012821DC7868F8B9DFF8F0C294453B +:1034300070EB010316D337E0276A27B96FF00C0051 +:1034400013B0BDE8F08F3B699845B5D03F68F4E70D +:10345000B24890427CEB010301D30020F0E7029BCD +:10346000002BFAD0079B0F2B17DCFA7DB30002F07C +:10347000030203F07C031343FB7539462046FFF734 +:1034800007FB6B7BBB76029B3BB9FB7DC3F38402DE +:10349000013262F38603FB75D0E76A7BBB7E9A42FA +:1034A000DBD1029B002B35D0B309022B32D0039B1A +:1034B000BB60049BFB60142200210DA8FDF7FCFDFE +:1034C000039B0A93049B0B932B1D0C932B7BADF852 +:1034D0003EB0013BDBB2ADF83C30069B8DF842308C +:1034E000059B8DF8433094F82C308DF840A083F084 +:1034F00001038DF844308DF84180A3680AA9204665 +:103500009847FB7DC3F38403013303F01F039B0241 +:10351000FB82A2E7FB7DC6F34012B2EBD31F40F063 +:10352000F980C3F38403434540F0FC80029A2B7B6F +:10353000B609002A52D016F0010661D1032B40F2E1 +:10354000F480039BBB60049BFB60FB8A66F309036A +:10355000FB822B7BAE1D033BDBB23246394604F1C6 +:103560000C00FFF7A7FA00280CDA39462046FFF7CF +:103570008FFAFB7DC3F38403013303F01F039B0227 +:10358000FB8205E7DDE90884AB883B834FF6FF73D8 +:10359000C9F12000A9F1200228FA09F104FA00F08B +:1035A000014324FA02F211431846C9B2FFF7C4F9E5 +:1035B00009F10809B9F1400F0346E9D1B8822A7B25 +:1035C000033AD2B23146FFF7C9F9FB7DB882DA433C +:1035D000C2F3C01262F3C713FB753EE786B92E1D16 +:1035E000013BDBB23246394604F10C00FFF762FAC8 +:1035F0000028BADB2A7BB88A013AD2B23146E2E728 +:10360000F98AC1F30901013B0429DAB25BD8281D0C +:10361000002307F11B069A4208D910F801CB06F8DF +:1036200001C0013101330529DBB2F4D103990A91BC +:1036300004990B91934207F11B010C9138BF04339D +:1036400079680D9134BF55FA83F300230E93FB8AFA +:10365000ADF83EB0C3F309031A44069B8DF842301F +:10366000059B8DF8433094F82C30ADF83C2083F066 +:1036700001038DF8443000238DF840A08DF841807F +:103680007B602A7BB88A013A291DFFF767F93B8BDB +:10369000B882834203D1A3680AA9204698472046EE +:1036A0000AA9FFF7FDFDFB7DBA8AC3F3840301334A +:1036B00003F01F039B02FB823B8B9A420CBF00204E +:1036C0006FF01000BCE67B68002BAFD0052001E056 +:1036D0001C3033461E68002EFAD1091A081D2E1D13 +:1036E000184401EB090CBCF11B0F5FFA89F39DD85C +:1036F0009A429BD916F8013B00F8013B09F10109F8 +:10370000EFE76FF009009BE66FF00A0098E66FF0B4 +:103710000B0095E66FF00D0092E600BF40420F00EF +:1037200080841E006FF00E008AE66FF00F0087E6BF +:10373000EFF3098305494A6B22F001024A636833BB +:1037400083F30988002383F31188704700EF00E0BA +:10375000302080F3118862B60C4B0D4AD96821F4F1 +:10376000E0610904090C0A43DA60D3F8FC20094936 +:1037700042F08072C3F8FC200A6842F001020A603D +:103780002022DA7783F82200704700BF00ED00E0C6 +:103790000003FA05001000E010B5302383F3118810 +:1037A0000E4B5B6813F4006314D0F1EE103AEFF3A4 +:1037B0000984683C4FF08073E361094BDB6B23663F +:1037C00084F3098800F0BAFA10B1064BA36110BD6A +:1037D000054BFBE783F31188F9E700BF00ED00E03C +:1037E00000EF00E03F03000842030008434B4FF4A2 +:1037F000007270B51A605A6912F4C06FFBD1404B69 +:103800009A6802F00C02042A20D01A6842F48072EE +:103810001A601A685205FCD501229A609A6802F073 +:103820000C02042AFAD13749374A0A600A6812F0B2 +:103830000F02FBD1C3F8982063221A601A6896031E +:10384000FCD42E4A4FF48071C2F88010C468E5039E +:1038500006D51A6842F480321A601A689103FCD5C2 +:10386000C269D20709D5D3F8982042F00102C3F803 +:103870009820D3F898209607FBD54269DA6044F483 +:1038800080721A6004F0807111B11A689501FBD53D +:10389000996802691B4E22F0030501F003012943D8 +:1038A000996085693560316869400907FBD1134922 +:1038B00005680D6046684E608068C1F880006E043F +:1038C00017D448698505FCD4996802F0030021F0FB +:1038D00003010143996092009968514011F00C0F67 +:1038E000FAD1E2055EBF1A6822F480721A600020E5 +:1038F00070BD48698005FCD5E6E700BF0070004058 +:1039000000100240002002400006040008B500F04C +:1039100083F9BDE8084000F05BB9000010B5394CF0 +:103920003948A36A4FF0FF32A262A36A0023A36260 +:10393000A16AE16A61F07F01E162E16A01F07F0161 +:10394000E162E16A216B2263216B2363216BA16B2E +:10395000A263A16BA363A16BE16BE263E16BE36321 +:10396000E16B216C2264226C2364226C226E42F093 +:1039700001022266D4F8802022F00102C4F88020DF +:10398000D4F88020A26D42F08052A265A26F22F08E +:103990008052A267A26F1D4A4FF400419160D3602C +:1039A000136253629362D362136353639363D3636B +:1039B000136453649364D36413655365116841F4CD +:1039C00080711160D4F8902012F4407F1EBF4FF434 +:1039D0008032C4F89020C4F890300D4A0023A360D0 +:1039E000C4F88820C4F89C30FFF700FF10B10948E4 +:1039F00000F0DAF9D4F8903023F00323C4F89030C3 +:103A000010BD00BF00100240FC48000800700040DC +:103A100055010051F4480008014B53F8200070474D +:103A200018230020074A08B5536903F001035361C6 +:103A300023B1054A13680BB150689847BDE80840A8 +:103A4000FFF7AABE0004014084650020074A08B5BC +:103A5000536903F00203536123B1054A93680BB124 +:103A6000D0689847BDE80840FFF796BE00040140C3 +:103A700084650020074A08B5536903F004035361C5 +:103A800023B1054A13690BB150699847BDE8084056 +:103A9000FFF782BE0004014084650020074A08B594 +:103AA000536903F00803536123B1054A93690BB1CD +:103AB000D0699847BDE80840FFF76EBE000401409A +:103AC00084650020074A08B5536903F01003536169 +:103AD00023B1054A136A0BB1506A9847BDE8084004 +:103AE000FFF75ABE0004014084650020164B10B554 +:103AF0005C6904F478725A61A30604D5134A936A88 +:103B00000BB1D06A9847600604D5104A136B0BB10D +:103B1000506B9847210604D50C4A936B0BB1D06BC0 +:103B20009847E20504D5094A136C0BB1506C9847CD +:103B3000A30504D5054A936C0BB1D06C9847BDE83A +:103B40001040FFF729BE00BF00040140846500203B +:103B5000194B10B55C6904F47C425A61620504D5C6 +:103B6000164A136D0BB1506D9847230504D5134ABF +:103B7000936D0BB1D06D9847E00404D50F4A136ED6 +:103B80000BB1506E9847A10404D50C4A936E0BB14B +:103B9000D06E9847620404D5084A136F0BB1506F7A +:103BA0009847230404D5054A936F0BB1D06F98470B +:103BB000BDE81040FFF7F0BD00040140846500201F +:103BC00008B500F0FBFCBDE80840FFF7E5BD0000CC +:103BD000062108B5084600F033F80621072000F05A +:103BE0002FF80621082000F02BF80621092000F00C +:103BF00027F806210A2000F023F80621172000F0FC +:103C00001FF80621282000F01BF8BDE80840072116 +:103C10001C2000F015B800004FF0E0230022586887 +:103C20004FF0FF31930003F1604303F5614301322C +:103C30009042C3F88010C3F88011F3D2704700009F +:103C400000F1604303F561430901C9B283F8001331 +:103C5000012200F01F039A4043099B0003F16043D7 +:103C600003F56143C3F880211A6070470023037590 +:103C7000826803691B6899689142FBD25A680360A5 +:103C800042601060586070470023037582680369C2 +:103C90001B6899689142FBD85A68036042601060C3 +:103CA0005860704708B50846302383F311880B7DB0 +:103CB000032B05D0042B0DD02BB983F3118808BD3D +:103CC0008B6900221A604FF0FF338361FFF7CEFF4C +:103CD0000023F2E7D1E9003213605A60F3E70000F5 +:103CE000FFF7C4BF054BD9680875186802681A60E9 +:103CF000536001220275D860FCF70CBBF86200200B +:103D000030B50C4BDD684B1C87B004460FD02B46FA +:103D1000094A684600F02AF92046FFF7E3FF009BB6 +:103D200013B1684600F02CF9A86907B030BDFFF761 +:103D3000D9FFF9E7F8620020A53C0008044B1A6897 +:103D4000DB6890689B68984294BF00200120704710 +:103D5000F8620020084B10B51C68D86822681A6009 +:103D6000536001222275DC60FFF78EFF014620467A +:103D7000BDE81040FCF7CEBAF862002038B5074C19 +:103D800007490848012300252370656000F044FCC2 +:103D90000223237085F3118838BD00BF60650020C1 +:103DA00020490008F862002008B572B6044B186577 +:103DB00000F0B4FA00F064FB024B03221A70FEE735 +:103DC000F86200206065002000F010B98B600223CB +:103DD00008618B82084670478368A3F1840243F828 +:103DE000142C026943F8442C426943F8402C094AD8 +:103DF00043F8242CC26843F8182C022203F80C2C38 +:103E0000002203F80B2C044A43F8102CA3F12000E5 +:103E1000704700BF2D030008F862002008B5FFF7C7 +:103E2000DBFFBDE80840FFF75BBF0000024BDB682B +:103E300098610F20FFF756BFF8620020302383F30C +:103E40001188FFF7F3BF000008B50146302383F364 +:103E500011880820FFF754FF002383F3118808BD61 +:103E600010B503689C68A2420CD85C688A600B603D +:103E70004C602160596099688A1A9A604FF0FF334C +:103E8000836010BD1B68121BECE700000A2938BFD5 +:103E90000A2170B504460D460A26601900F0B6FBEB +:103EA00000F0A2FB041BA54203D8751C2E46044655 +:103EB000F3E70A2E04D9BDE87040012000F0ECBB06 +:103EC00070BD0000F8B5144B0D46D96103F1100127 +:103ED00041600A2A1969826038BF0A22016048607D +:103EE0001861A818144600F083FB0A2700F07CFB39 +:103EF000431BA342064606D37C1C281900F086FB10 +:103F000027463546F2E70A2F04D9BDE8F8400120DC +:103F100000F0C2BBF8BD00BFF8620020F8B506464D +:103F20000D4600F061FB0F4A134653F8107F9F4285 +:103F300006D12A4601463046BDE8F840FFF7C2BF29 +:103F4000D169BB68441A2C1928BF2C46A34202D958 +:103F50002946FFF79BFF224631460348BDE8F8405B +:103F6000FFF77EBFF86200200863002010B4C0E9AC +:103F7000032300235DF8044B4361FFF7CFBF00002C +:103F800010B5194C236998420DD0D0E900328168F0 +:103F900013605A609A680A449A60002303604FF0E5 +:103FA000FF33A36110BD2346026843F8102F53600E +:103FB0000022026022699A4203D1BDE8104000F05D +:103FC0001FBB936881680B44936000F00DFB22696E +:103FD000E1699268441AA242E4D91144BDE8104054 +:103FE000091AFFF753BF00BFF86200202DE9F04720 +:103FF000DFF8BC8008F110072C4ED8F8105000F004 +:10400000F3FAD8F81C40AA68031B9A423ED814441D +:10401000D5E900324FF00009C8F81C4013605A601F +:10402000C5F80090D8F81030B34201D100F0E8FA9A +:1040300089F31188D5E9033128469847302383F363 +:1040400011886B69002BD8D000F0CEFA6A69A0EB1A +:1040500004094A4582460DD2022000F01DFB0022D1 +:10406000D8F81030B34208D151462846BDE8F04791 +:10407000FFF728BF121A2244F2E712EB090938BFF2 +:104080004A4629463846FFF7EBFEB5E7D8F8103028 +:10409000B34208D01444211AC8F81C00A960BDE836 +:1040A000F047FFF7F3BEBDE8F08700BF08630020CC +:1040B000F862002038B500F097FA054AD2E90845C1 +:1040C000031B181945F10001C2E9080138BD00BF02 +:1040D000F862002000207047FEE7000070470000F3 +:1040E0004FF0FF3070470000BFF34F8F024A136953 +:1040F000DB03FCD4704700BF0020024008B5094B29 +:104100001B7873B9FFF7F0FF074B5A69002ABFBF4E +:10411000064A9A6002F188329A601A6822F4806234 +:104120001A6008BD78650020002002402301674521 +:1041300008B50B4B1B7893B9FFF7D6FF094B5A69AB +:1041400042F000425A611A6842F480521A601A68BA +:1041500022F480521A601A6842F480621A6008BD24 +:104160007865002000200240FF289ABF00F58030CB +:10417000C0020020704700004FF40060704700004C +:104180004FF4807070470000FF2808B50BD8FFF788 +:10419000EBFF00F500630268013204D10430834272 +:1041A000F9D1012008BD0020FCE70000FF2838B548 +:1041B000044624D8FFF798FFFFF7A0FF114AF32326 +:1041C000136102235361C3005169C50903F47E736F +:1041D00043EAC5230B435361536943F4803353616E +:1041E000FFF782FF4FF40061FFF7BEFF00F044F9D4 +:1041F000FFF79EFF2046BDE83840FFF7C5BF00200F +:1042000038BD00BF002002402DE9F84340EA020318 +:1042100013F00703144606D0304B40F242321A60C6 +:104220000020BDE8F88385182D4A95420CD92B4A09 +:1042300040F247311160F3E7031D1B684A6893425F +:1042400008D1083C08300831072C14D902680B68E3 +:104250009A42F1D0FFF752FFFFF746FF214E083197 +:104260004FF001084FF00009012CA1F1080706D812 +:10427000FFF75EFF01E0002CECD10120D1E7C6F88A +:104280001480054651F8083C45F8043B51F8043CBD +:104290004360FFF729FF336943F001033361C6F838 +:1042A0001490026851F8083C9A420CD00B4B40F233 +:1042B0006F321A600C4B18600C4B1C600C4B1F606B +:1042C000FFF736FFACE72D6851F8043C9D4201F141 +:1042D0000801EBD1083C0830C6E700BF7465002038 +:1042E000000008080020024068650020706500207A +:1042F0006C650020084908B50B7828B11BB9FFF799 +:10430000FDFE01230B7008BD002BFCD0BDE808406A +:104310000870FFF70DBF00BF7865002008B506499B +:10432000064800F0ABF8BDE808404FF400414FF0FC +:10433000805000F0A3B800BF007F01000001002002 +:10434000084600F035BA000038B5EFF311859DB985 +:10435000EFF30584C4F30804302334B183F31188E8 +:10436000FFF7A8FE85F3118838BD83F31188FFF7A6 +:10437000A1FE84F3118838BDBDE83840FFF79ABE2E +:1043800038B5FFF7E1FF114C114AC00840EA41700F +:10439000A0FB025EC908A0FB040C1CEB050CA1FBF2 +:1043A00004404FF000035B41A1FB02121CEB040C24 +:1043B00043EB000011EB0E0142F10002411842F103 +:1043C0000000090941EA007038BD00BFCFF753E390 +:1043D000A59BC4200244D2B2904200D17047431C36 +:1043E000800000F1804000F51450006841F8040B93 +:1043F000D8B2F1E7124B10B5D3F89040240409D499 +:10440000D3F89040C3F89040D3F8904044F400446F +:10441000C3F890400B4C2368024443F4807323603C +:10442000D2B2904200D110BD431C800000F1804008 +:1044300000F5145051F8044B0460D8B2F1E700BF06 +:10444000001002400070004007B5012201A90020C1 +:10445000FFF7C0FF019803B05DF804FB13B50446F5 +:10446000FFF7F2FFA04205D0012201A9002001942C +:10447000FFF7C0FF02B010BD70470000704700009A +:1044800070470000074B45F255521A6002225A60ED +:1044900040F6FF729A604CF6CC421A60024B012241 +:1044A0001A7070470030004080650020034B1B7875 +:1044B0001BB1034B4AF6AA221A60704780650020A0 +:1044C00000300040054B1A6832B902F1804202F513 +:1044D0000432D2F894201A60704700BF7C65002037 +:1044E000024B4FF40002C3F89420704700100240C2 +:1044F00008B5FFF7E7FF024B1868C0F3407008BD2E +:104500007C65002070470000FEE700000A4B0B4866 +:104510000B4A90420BD30B4BDA1C121AC11E22F02D +:1045200003028B4238BF00220021FCF7C5BD53F8BF +:10453000041B40F8041BECE7A44A000804660020B2 +:1045400004660020046600200023054A1946013352 +:10455000102BC2E9001102F10802F8D1704700BF28 +:104560008465002008B5124B9A6D42F001029A65ED +:104570009A6F42F001029A670E4A9B6F936843F06C +:10458000010393600620FFF747FA0B4BB0FBF3F0F3 +:104590004FF080434FF0FF3201389862DA62002218 +:1045A0009A615A63DA605A6001225A611A6008BD42 +:1045B00000100240002004E040420F004FF0804213 +:1045C00008B51169D3680B40D9B2C9439B07116183 +:1045D00007D5302383F31188FFF7F6FB002383F31D +:1045E000118808BDFFF7BEBF4FF08043586A70477F +:1045F0004FF08043002258631A610222DA6070474C +:104600004FF080430022DA60704700004FF0804393 +:1046100058637047FEE7000070B51B4B016300252F +:10462000044686B0586085620E46FFF791F804F1A3 +:104630001003C4E904334FF0FF33C4E90635C4E97D +:104640000044A560E562FFF7CFFF2B460246C4E9B0 +:10465000082304F134010D4A256580232046FFF725 +:10466000B5FB0123E0600A4A03750092726801926B +:10467000B268CDE90223074B6846CDE90435FFF760 +:10468000CDFB06B070BD00BF606500202C4900085E +:104690003149000815460008024AD36A1843D0621F +:1046A000704700BFF86200204B6843608B688360EE +:1046B000CB68C3600B6943614B6903628B694362DA +:1046C0000B6803607047000008B5204BDA6A42F0BF +:1046D0007F02DA62DA6A22F07F02DA62DA6ADA6C80 +:1046E00042F07F02DA64DA6E42F07F02DA66184A3C +:1046F000DB6E11464FF09040FFF7D6FF02F11C0130 +:1047000000F58060FFF7D0FF02F1380100F580600E +:10471000FFF7CAFF02F1540100F58060FFF7C4FF04 +:1047200002F1700100F58060FFF7BEFF02F18C011D +:1047300000F58060FFF7B8FF02F1A80100F5806086 +:10474000FFF7B2FFBDE80840FFF7E8B800100240ED +:104750003849000808B500F009F8FFF70FFBBDE87D +:104760000840FFF7AFBE00007047000008B5FFF734 +:10477000CDF8FFF7E9FEFFF7F7FFBDE80840FFF7C8 +:1047800031BF00000B460146184600F003B8000098 +:1047900000F00EB810B5054C13462CB10A46014680 +:1047A0000220AFF3008010BD2046FCE700000000AF +:1047B000024B01461868FFF7C3BD00BF402300202D +:1047C00010B501390244904201D1002005E0037880 +:1047D00011F8014FA34201D0181B10BD0130F2E7C0 +:1047E0002DE9F041A3B1C91A17780144044603F139 +:1047F000FF3C8C42204601D9002009E00578BD42EB +:1048000004F10104F5D10CEB0405D618A54201D141 +:10481000BDE8F08115F8018D16F801EDF045F5D0F1 +:10482000E7E70000034611F8012B03F8012B002AEB +:10483000F9D170476F72672E6172647570696C6F21 +:10484000742E4D6174656B473437342D4453686F53 +:104850007400000040A2E4F1646891060041A3E501 +:10486000F2656992070000004261642043414E49AD +:104870006661636520696E6465782E000001000042 +:104880000001FF00006400400068004000000000DC +:1048900000000000911E00081D190008F525000801 +:1048A0008D190008D1190008B91B000899190008D2 +:1048B000551900085919000831190008191900087C +:1048C000751B00083D1900085D27000849190008FC +:1048D000491B000801040E05054B02020E05054B9D +:1048E00004010E05054B05010B04044B08010603EA +:1048F00003460000636C6B737763000000030000E5 +:1049000000000000000100000000010103000000A1 +:104910000328310104070400010000006330000097 +:104920001C49000850630020606500206D61696EBD +:104930000069646C650000000000802A000000002F +:10494000AAAAAAAA00000024FFFF0000000000009D +:10495000009009000028000100000000AAAAAAAAED +:1049600000000001FFFF00000000900900000000AF +:104970000000001400000000AAAAAAAA000000106B +:10498000FFDF000000000000000000000000000049 +:1049900000000000AAAAAAAA00000000FFFF000071 +:1049A0000000000000000000000000000000000007 +:1049B000AAAAAAAA00000000FFFF00000000000051 +:1049C000000000000000000000000000AAAAAAAA3F +:1049D00000000000FFFF00000000000000000000D9 +:1049E0000000000000000000AAAAAAAA000000001F +:1049F000FFFF0000000000000000000000000000B9 +:104A00009204000000000000007007000000000099 +:104A1000FE2A0100D2040000006889096D8BB902EA +:104A200000B4C4040068890900688909006889091C +:104A30000068890900688909006889090000000088 +:104A400044230020000000000000000000000000DF +:104A50000000000000000000000000000000000056 +:104A60000000000000000000000000000000000046 +:104A70000000000000000000000000000000000036 +:104A80000000000000000000000000000000000026 +:104A90000000000000000000000000000000000016 +:044AA0000000000012 +:00000001FF diff --git a/Tools/bootloaders/MatekG474-Periph_bl.bin b/Tools/bootloaders/MatekG474-Periph_bl.bin new file mode 100755 index 0000000000000..12b8c44114133 Binary files /dev/null and b/Tools/bootloaders/MatekG474-Periph_bl.bin differ diff --git a/Tools/bootloaders/MatekG474-Periph_bl.hex b/Tools/bootloaders/MatekG474-Periph_bl.hex new file mode 100644 index 0000000000000..69a3822bc3524 --- /dev/null +++ b/Tools/bootloaders/MatekG474-Periph_bl.hex @@ -0,0 +1,1197 @@ +:020000040800F2 +:1000000000070020F101000845270008FD26000830 +:1000100025270008FD2600081D270008F301000819 +:10002000F3010008F3010008F3010008313700086C +:10003000F3010008F3010008F3010008F3010008D0 +:10004000F3010008F3010008F3010008F3010008C0 +:10005000F3010008F3010008253A00084D3A0008B2 +:10006000753A00089D3A0008C53A0008F3010008F7 +:10007000F3010008F3010008F3010008F301000890 +:10008000F3010008F3010008F3010008F301000880 +:10009000F3010008AD260008C1260008ED3A00086B +:1000A000F3010008F3010008F3010008F301000860 +:1000B000C13B0008F3010008F3010008F301000848 +:1000C000F3010008F3010008F3010008F301000840 +:1000D000F3010008F3010008F3010008F301000830 +:1000E000513B0008F3010008F3010008F301000888 +:1000F000F3010008F3010008F3010008F301000810 +:10010000F3010008F3010008F3010008F3010008FF +:10011000F3010008F3010008F3010008F3010008EF +:10012000F3010008F3010008F3010008F3010008DF +:10013000F3010008F3010008F3010008F3010008CF +:10014000F3010008F3010008F3010008F3010008BF +:10015000F3010008F3010008F3010008F3010008AF +:10016000F3010008F3010008F3010008F30100089F +:10017000F3010008F3010008F3010008F30100088F +:10018000F3010008F3010008F3010008F30100087F +:10019000F3010008F3010008D5260008E92600084D +:1001A000F3010008F3010008F3010008F30100085F +:1001B000F3010008F3010008F3010008F30100084F +:1001C000F3010008F3010008F3010008F30100083F +:1001D000F3010008F3010008F3010008F30100082F +:1001E000990F00080000000000000000000000005F +:1001F00002E000F000F8FEE772B6374880F30888A6 +:10020000364880F3098836483649086040F20000D5 +:10021000CCF200004EF63471CEF200010860BFF35C +:100220004F8FBFF36F8F40F20000C0F2F0004EF628 +:100230008851CEF200010860BFF34F8FBFF36F8F7C +:100240004FF00000E1EE100A4EF63C71CEF20001D4 +:100250000860062080F31488BFF36F8F04F052F912 +:1002600004F032FA4FF055301F491B4A91423CBF0F +:1002700041F8040BFAE71D49184A91423CBF41F886 +:10028000040BFAE71A491B4A1B4B9A423EBF51F82E +:10029000040B42F8040BF8E700201849184A914271 +:1002A0003CBF41F8040BFAE704F030F904F052FACD +:1002B000144C154DAC4203DA54F8041B8847F9E797 +:1002C00000F042F8114C124DAC4203DA54F8041B12 +:1002D0008847F9E704F018B9000700200023002040 +:1002E0000000000808ED00E00001002000070020E9 +:1002F000004A000800230020A4230020A823002097 +:1003000004660020E0010008E4010008E4010008A0 +:10031000E40100082DE9F04F2DED108AC1F80CD052 +:10032000C3689D46BDEC108ABDE8F08F002383F3BF +:1003300011882846A047002003F080FDFEE703F067 +:1003400009FD00DFFEE70000F8B500F03BFE04F019 +:100350007BF8074604F0CCF80546C0BB294B9F420A +:1003600035D001339F4235D0274B27F0FF029A4208 +:1003700033D1F8B200F058FC2E4642F2107400F06F +:1003800059FC08B10024264601F00EF948B30320B9 +:1003900000F03EF80024264635B11C4B9F4203D0A6 +:1003A00004F09EF800242646002004F057F80EB111 +:1003B00000F044F800F070FC02F0CCF90546C4B936 +:1003C00000F0BEFC4FF47A7003F03EFDF7E72E46D6 +:1003D0000024D4E704460126D1E7064640F6C414BB +:1003E000CDE740F6C4139C4204BF4FF47A74012653 +:1003F000D2E702F0AFF9431BA342E1D900F01EF8A7 +:10040000DAE700BF010007B0000008B0263A09B0E3 +:10041000084B187003280CD8DFE800F00805020824 +:10042000022000F02DBE022000F020BE024B002270 +:100430005A607047A8230020AC23002010B501F0BB +:10044000B3F830B1234B03221A70234B00225A60B9 +:1004500010BD224B224A1C4619680131F8D00433E2 +:100460009342F9D16268A242F2D31E4B9B6803F11A +:10047000006303F510439A42EAD204F003F804F053 +:1004800015F8002000F0B8FD0220FFF7C1FF164B61 +:100490009A6D00229A65996F9A67996FD96DDA659E +:1004A000D96FDA67D96F196E1A66D3F88010C3F85E +:1004B0008020D3F8803072B64FF0E0233021C3F8AB +:1004C000084DD4E9003281F311889D4683F30888F2 +:1004D0001047BDE7A8230020AC23002000900008AF +:1004E000209000080023002000100240094A1368F1 +:1004F00049F2690099B21B0C00FB01331360064BF3 +:10050000186844F2506182B2000C01FB02001860CE +:1005100080B27047142300201023002010B5002162 +:100520001022044600F0C8FD034B03CB206061603D +:100530001868A06010BD00BF9075FF1F2DE9F04145 +:10054000ADF5507D0DF13C086EAC40F275120746DA +:100550000D4610A80021C8F8001000F0ADFD4FF4C2 +:10056000C4720021204600F0A7FD02F0F3F8274BEB +:100570004FF47A72B0FBF2F0186093E807000223A0 +:1005800084E807000DF5ED702382FFF7C7FF49F2FD +:1005900004231F49238407A804F044F91E2384F888 +:1005A00032310DF2EB2207AB0DF1340C1E4603CEB7 +:1005B000664510605160334602F10802F6D130689A +:1005C0001060B388938041460122204600F0C0FDB0 +:1005D00000230393AB7E029305F11903019380B2CC +:1005E0000123CDE904800093E97E06A3D3E900232B +:1005F000384602F06DFC0DF5507DBDE8F08100BF7E +:10060000AFF300809E6AC421818A46EEB4230020A5 +:10061000344800082DE9F0412C4C237ADAB08046AA +:100620000D465BBB27A9284600F0B4FE074600280C +:1006300042D19DF89D60C82E3ED801464FF4A66277 +:10064000204600F039FD4FF48073C4F8F8314FF4C0 +:100650000073C4F80C334FF44073C4F820343246AE +:100660000DF19E0104F1090000F014FD26449DF8EF +:100670009C30777223720BB9EB7E237281220021AA +:1006800006AC27A800F018FD0122214627A800F09B +:10069000C7FE00230393AB7E029305F1190380B2DA +:1006A00001932823CDE904400093E97E05A3D3E913 +:1006B0000023404602F00CFC5AB0BDE8F08100BFB8 +:1006C000AFF3008026417272DF25D7B7805D00202E +:1006D000F0B5254E4FF48A7505FB0065F1B096F82C +:1006E000D83085F8DC300024D822214685F8E8404F +:1006F0003AA800F0E1FC06F1090000F0D5FCD5F8BD +:10070000E4308DF8F000C2B206AF06F109010DF138 +:10071000F100CDE93A3400F0BDFC394601223AA897 +:1007200000F0B4FE80B2CDE9047008230127CDE9C2 +:10073000023706F1D803019330230093317A0B4836 +:1007400007A3D3E9002302F0C3FBA04206DD02F0B9 +:1007500001F8C5F8E000384671B0F0BD2046FBE76F +:1007600078F6339F93CACD8D805D0020CC33002076 +:100770002DE9F04F264FDFF8A480264E87B038468B +:1007800002F0D2FB034600283AD00024CDE903440E +:10079000ADF81440027B8DF81420996840680294EB +:1007A00003AA03C21B681C4D43F000430293A146F9 +:1007B000A2462B68D3F810B001F0CEFF10EB080270 +:1007C00041F100032846CDF800A002A9D84704F55E +:1007D000A6640028C8BF49F00109B4F5266F05F5E5 +:1007E000A655E6D1B9F1000F05D0384602F0A0FBBE +:1007F00086F800A0C3E73378072B04D801333370A1 +:1008000007B0BDE8F08F024802F092FBF8E700BFA6 +:10081000CC330020B56200200034002040420F009D +:1008200070B50D4614461E4602F0AEFA50B9022EBF +:1008300010D1012C0ED112A3D3E90023C5E9002366 +:10084000012007E0282C10D005D8012C09D0052C58 +:100850000FD0002070BD302CFBD10BA3D3E90023B7 +:10086000ECE70BA3D3E90023E8E70BA3D3E90023CC +:10087000E4E70BA3D3E90023E0E700BFAFF3008078 +:10088000401DA12026812A0B78F6339F93CACD8D77 +:100890009E6AC421818A46EE26417272DF25D7B74F +:1008A000F017304A39059E5638B505460E4C0021E2 +:1008B000013500F0C3FBA4F82C55B4F82C0500F06A +:1008C000A5FB78B1B4F82C0500F0B0FB014648B99F +:1008D000B4F82C0500F0B2FBB4F82C350133A4F8C1 +:1008E0002C35EAE738BD00BF805D0020F8B50D4C1F +:1008F0000D4F0226A4F5805343F8307C237E3BB98C +:1009000065692DB1284600F0CDFE284603F040FF72 +:10091000204600F0C7FE012EA4F5A65400D1F8BD74 +:100920000126E7E7F0580020944800082DE9F04F31 +:100930008FB000AF05460C4602F026FA002849D1D8 +:10094000237E022B1BD1E38A012B18D101F002FF79 +:100950000646FFF7CBFD03464FF4C870DFF8C482AC +:10096000B3FBF0F206F5167602FB103316FA83F3AA +:10097000C8F80030E37E33B9A34B00221A703C372D +:10098000BD46BDE8F08F07F12401204600F0B6FC1B +:100990000028F4D107F11400FFF7C0FD97F82640B6 +:1009A00007F11401224607F1270003F009FF002890 +:1009B000E2D10F2C08D8944B1C70D8F80030A3F566 +:1009C0001673C8F80030DAE797F82410284602F0CA +:1009D000D3F9D4E7E38A282B2BD010D8012B23D0CE +:1009E000052BCCD1BFF34F8F8849894BCA6802F4DD +:1009F000E0621343CB60BFF34F8F00BFFDE7302BA6 +:100A0000BDD1844EE17E327A9142B8D1607E3146CA +:100A1000002291F8DC50854200F0A5800132042AC2 +:100A200001F58A71F5D1AAE721462846FFF786FD30 +:100A3000A5E721462846FFF7EDFDA0E7B2F8EC5008 +:100A40007B6005F103094FEA99094FEA8902D11D3C +:100A5000C908A8EBC1039D46EB460021584600F0AB +:100A60002BFB04F1EE012A463144584600F012FBFC +:100A70007B6813B9012000F0BFFA96F8D20000F0AD +:100A8000C5FA044630B9307200F0E0FA204600F0B2 +:100A9000B3FAB1E0D6F8D4203AB996F8D200B6F855 +:100AA0002C25824201D8FFF7FFFED6F8D4202A4435 +:100AB000944208D296F8D200B6F82C250130824232 +:100AC00001D8FFF7F1FE70685FFA89F2594600F02D +:100AD000FBFA08B9C54679E0726896F8D2002A4454 +:100AE0007260D6F8D42005EB0209C6F8D49000F065 +:100AF0008DFA814509D396F8D220D6F8D400013278 +:100B0000001B86F8D220C6F8D400FF2D0FD8002491 +:100B1000347200F09BFA204600F06EFA00F044FDBB +:100B20003D4B188108B9FFF789FCC54627E7BB682C +:100B300096F8D9000AFB0362FB68D2F8E41082F849 +:100B4000E83001F58061C2F8E030C2F8E410FFF748 +:100B5000BFFDFFF70DFE96F8D920013202F0030227 +:100B600086F8D920B6E74FF48A7A0AFB02F505F138 +:100B7000EA013144204600F0BBFCF86000287FF415 +:100B8000FEAE3544012285F8E82001F0E3FDD5F8FA +:100B9000E020D6ED007ADFED216A801A192838BFEF +:100BA000192040F6B832904228BF1046B8EE677A56 +:100BB00007EE900AF8EEE77A67EEA67ADFED186A9C +:100BC000E7EE267AFCEEE77AC6ED007A96F8D930A1 +:100BD000BB60BA6873680AFB02F4321992F8E81035 +:100BE00059B1D2F8E4108B42E8463FF427AF002118 +:100BF00082F8E810C2F8E010C5467368064A9B0AFE +:100C000001331381BBE600BFC533002000ED00E0D7 +:100C10000400FA05805D0020B4230020CDCCCC3D3B +:100C20006666663FC8330020014B1870704700BFEE +:100C3000C023002038B54FF00054134B22689A426D +:100C400020D1124B627D12481A70237D03724FF43B +:100C50008073C0F8F8314FF40073C0F80C330025EE +:100C60004FF44073C0F820340A49C0F8E450C92258 +:100C7000093000F00FFAE0222946204600F01CFA65 +:100C8000012038BD0020FCE79AAD44C5C0230020F8 +:100C9000805D00201600002037B500F085FC1F4C59 +:100CA0001F4D2049288102236B71236801225B6854 +:100CB0002046984704F580531A49D3F8C0340122DE +:100CC0005B6804F5A650984700230193164B17491B +:100CD00000931748174B4FF4805202F025F8164B3B +:100CE000197811B1124802F047F801F033FD0446BB +:100CF000FFF7FCFB4FF4C873B0FBF3F202FB1303E6 +:100D000004F5167010FA83F00C4B186003F0F0FB3A +:100D100008B10F232B8103B030BD00BF0034002089 +:100D2000B423002040420F0021080008C423002003 +:100D3000CC3300202D090008C0230020C833002038 +:100D40002DE9F04F2DED028B002493B00DF12C080E +:100D50009FED818BDFF83C92FFF70AFD0A94ADF816 +:100D600034400B94C8F804400026814DDFF804B2EB +:100D7000374601238DF81C302B688DF81D408DED12 +:100D8000008B0DF11D02D3F808A007A90023284607 +:100D9000D0479DF81CA0BAF1000F24D0D9F8143028 +:100DA00083F40053C9F81430102200210EA800F07B +:100DB00083F92B6808AA5F690AA90DF11E0328466A +:100DC000B84798E803000FAB83E803009DF8343080 +:100DD0008DF844300A9B0E930EA9DDE9082358468E +:100DE00002F084FA574606F5A666B6F5266F05F5B5 +:100DF000A655BED1002FB7D15E4801F0C5FF00282F +:100E00003FD15D4E01F0A6FC3368984239D301F022 +:100E1000A1FC0546FFF76AFB4FF4C873B0FBF3F281 +:100E200002FB130305F5167010FA83F03060534E81 +:100E30008DF82870377817B901238DF82830C7F15D +:100E40001005EDB20EA8FFF769FB062D28BF062599 +:100E50000EAB2A46D9190DF1290000F01BF90AAB97 +:100E60000393182302930135454B0193EDB20123FF +:100E70000093404804953AA3D3E9002301F0CAFF48 +:100E8000347001F067FC3F4A3F4D1368C31AB3F555 +:100E90007A7F2FD3106001F05FFC02460B46354885 +:100EA00002F050F8334801F06FFF18B32B7A374E39 +:100EB000002B14BF03230223737101F04BFC0EAF10 +:100EC0004FF47A730122B0FBF3F0394630603046BC +:100ED00000F0ECF9182302932D4B019380B240F2FD +:100EE0005513CDE90370009322481FA3D3E90023D3 +:100EF00001F090FF2B7A93B101F02CFC00260746FD +:100F00004FF48A7895F8D900304400F0030008FBCC +:100F1000005393F8E82072B10136042EF2D1C820B4 +:100F200002F092FF2B7A002B7FF410AF13B0BDECD0 +:100F3000028BBDE8F08FD3F8E02042B12B68FA2B8A +:100F400038BFFA23BA1A0533B2EB430FE4D3FFF7E5 +:100F5000BFFB0028E0D1E2E7000000000000000035 +:100F6000401DA12026812A0BF1C6A7C1D068080F19 +:100F700000340020CC330020C8330020C5330020CB +:100F8000C4330020B0620020805D0020B423002024 +:100F9000B46200200008004810B5074C204600F05D +:100FA000B3FE04F5A65000F0AFFEBDE81040034AC2 +:100FB0000349002003F0E6BB00340020F462002067 +:100FC000ED08000870B503F0DBF8094E094D3080DC +:100FD000002428683388834208D903F0CDF82B68B1 +:100FE00004440133B4F5104F2B60F2D370BD00BF41 +:100FF000E4620020B862002003F07CB900F10060D8 +:10100000920000F5104003F0FFB80000054B1A688D +:10101000054B1B889B1A834202D9104403F0ACB8DD +:1010200000207047B8620020E4620020024B1B6879 +:10103000184403F0A9B800BFB8620020024B1B6837 +:10104000184403F0B3B800BFB8620020064991F815 +:10105000243033B10023086A81F824300822FFF7D6 +:10106000CDBF0120704700BFBC620020022802BF34 +:10107000024B4FF000529A61704700BF00080048D1 +:10108000022802BF024B4FF400529A61704700BF22 +:101090000008004810B50023934203D0CC5CC45430 +:1010A0000133F9E710BD000003460246D01A12F9D9 +:1010B000011B0029FAD1704702440346934202D033 +:1010C00003F8011BFAE770472DE9F8431F4D14465A +:1010D00095F824200746884652BBDFF870909CB3F1 +:1010E00095F824302BB92022FF2148462F62FFF7C4 +:1010F000E3FF95F82400C0F10802A24228BF22466F +:10110000D6B24146920005EB8000FFF7C3FF95F889 +:101110002430A41B1E44F6B2082E17449044E4B2B7 +:1011200085F82460DBD1FFF791FF0028D7D108E0D4 +:101130002B6A03EB82038342CFD0FFF787FF00289F +:10114000CBD10020BDE8F8830120FBE7BC62002082 +:101150002DE9F8430D46044600219046284640F20A +:101160007912FFF7A9FF234620220021284602F02A +:101170005FF8231D02222021284602F059F8631D42 +:1011800003222221284602F053F8A31D0322252121 +:10119000284602F04DF804F10803102228212846C1 +:1011A00002F046F804F1100308223821284602F024 +:1011B0003FF804F1110308224021284602F038F8D4 +:1011C00004F1120308224821284602F031F804F104 +:1011D000140320225021284602F02AF804F11803B3 +:1011E00040227021284602F023F804F1200308224F +:1011F000B021284602F01CF804F121030822B8218E +:10120000284602F015F804F12207C0263B46314675 +:1012100008222846083602F00BF8B6F5A07F07F141 +:101220000107F3D1314604F132030822284601F0C8 +:10123000FFFF94F83260002704F13309F900BE4241 +:1012400001F5A4711FD8F70007F5A476B8F1000FD7 +:1012500008D1314604F599730722284601F0E8FFCA +:1012600007F24F1694F83201502828BF5020074645 +:1012700004EB0009B046A1450DD106EBC7000730CD +:10128000C008BDE8F88309EB07030822284601F0EF +:10129000CFFF0137D2E704F2331341460822284634 +:1012A00001F0C6FF08F108080134E4E713B504466D +:1012B0000846002101602346C0F803102022019057 +:1012C00001F0B6FF0198231D0222202101F0B0FF9A +:1012D0000198631D0322222101F0AAFF0198A31D9A +:1012E0000322252101F0A4FF019804F10803102234 +:1012F000282101F09DFF072002B010BDF7B5047F43 +:1013000005460E462CB1838A122B02D9012003B068 +:10131000F0BD0023194607220096284601F04CFE36 +:10132000731C0093012200230721284601F044FE8C +:10133000D4B9B31C0093052223460821284601F0A6 +:101340003BFE0D24B378102BE0D83746B278BB1B98 +:10135000934210D32B7FA88A0734E408B3B98442A0 +:1013600094BF00200120D2E7AB8ADB00083BDB08FA +:10137000B3700824E6E7FB1C0093214600230822F3 +:10138000284601F019FE08340137DFE7201A18BF9C +:101390000120BCE7F7B5047F05460E462CB1838AD1 +:1013A000CA2B02D9012003B0F0BD002319460096D4 +:1013B0000822284601F000FE731CD4B908220093CD +:1013C00011462346284601F0F7FD10247378C82BF8 +:1013D000E8D8012372785F1C013B934210D32B7F26 +:1013E000A88A0734E408B3B9844294BF00200120DE +:1013F000D9E7AB8ADB00083BDB0873700824E5E71C +:10140000F3190093214600230822284601F0D4FD59 +:1014100008343B46DEE7201A18BF0120C3E700006E +:101420002DE9F8430D460446164600218122284640 +:10143000FFF742FE234608220021284601F0F8FE6D +:10144000C6B9631C07220821284601F0F1FE0F26C9 +:1014500094F901306778002BB8BF7F2704EB0709A8 +:10146000B0464C4508D10736082010FB0760C0087D +:10147000BDE8F8830826EBE7A31C4146082228466E +:1014800001F0D6FE08F108080134EAE72DE9F04141 +:101490000D46044616460021CE222846FFF70CFED4 +:1014A000234628220021284601F0C2FEBEB904F1DD +:1014B000080308222821284601F0BAFE302614F835 +:1014C000080FC82828BFC82080460027B84506EB6B +:1014D000C70106D806EBC800C008BDE8F081282681 +:1014E000EDE70137E3190822284601F0A1FEEDE7F8 +:1014F000F7B5047F05460E4634B1838AB3F5827F83 +:1015000002D9012003B0F0BD009601231022002172 +:10151000284601F051FDDCB9B31C00930922234693 +:101520001021284601F048FD19247388B3F5807F07 +:10153000E7D837467288BB1B934210D32B7FA88A0B +:101540000734E408B3B9844294BF00200120D9E7EE +:10155000AB8ADB00103BDB0873801024E5E73B1D02 +:101560000093214600230822284601F025FD083477 +:101570000137DFE7201A18BF0120C3E730B5094D56 +:101580000A4491420DD011F8013B5840082340F322 +:101590000004013B2C4013F0FF0384EA5000F6D115 +:1015A000EFE730BD2083B8EDF7B5384A10685168D1 +:1015B0006B4603C36A4636493648082303F010F9E0 +:1015C0000446002833D10A25334A106851686B4617 +:1015D00003C36A4631492F48082303F001F9044642 +:1015E000002849D00369B3F5EE2F45D8B0F866104E +:1015F00040F2924291423FD1294A024402F15C01F9 +:101600008B4239D35C3B234900209E1AFFF7B6FF7B +:101610003246074604F164010020FFF7AFFFA368DC +:101620009F4229D1E368984208BF002524E003695E +:10163000B3F5EE2F27D8418B40F29242914220D150 +:10164000174A024402F110018B4218D3103B114992 +:1016500000209D1AFFF792FF2A46064604F1180162 +:101660000020FFF78BFFA3689E4202D1E3689842F7 +:1016700001D00D25A8E70025284603B0F0BD1025B0 +:10168000A2E70C25A0E70B259EE700BF5448000801 +:10169000DC6F0700009000085D480008906F0700AD +:1016A0000870FFF710B5037C044613B9006803F017 +:1016B0007FF8204610BD00000023BFF35B8FC3609E +:1016C000BFF35B8FBFF35B8F8360BFF35B8F7047AC +:1016D000BFF35B8F0068BFF35B8F704770B5054643 +:1016E0000C30FFF7F5FF05F1080604463046FFF71A +:1016F000EFFFA04206D930466D68FFF7E9FF2544A9 +:10170000281A70BD3046FFF7E3FF201AF9E7000002 +:1017100070B50546406898B105F10800FFF7D8FF9D +:1017200005F10C0604463046FFF7D2FF84423046EE +:1017300094BF6D680025FFF7CBFF013C2C44201AB5 +:1017400070BD000038B50C460546FFF7C7FFA04244 +:1017500010D305F10800FFF7BBFF04446868B4FB31 +:10176000F0F100FB1144BFF35B8F0120AC60BFF3CD +:101770005B8F38BD0020FCE72DE9F0411446074699 +:101780000D46FFF7C5FF844228BF0446D4B1B846D2 +:1017900058F80C6B4046FFF79BFF304428604046EA +:1017A0007E68FFF795FF331A9C4203D86C600120D6 +:1017B000BDE8F0816B60A41B3B68AB602044E8602F +:1017C0000220F5E72046F3E738B50C460546FFF75B +:1017D0009FFFA04210D305F10C00FFF779FF0444EE +:1017E0006868B4FBF0F100FB1144BFF35B8F01208C +:1017F000EC60BFF35B8F38BD0020FCE72DE9FF41B3 +:10180000884669460746FFF7B7FF6C4606B204EB09 +:10181000C6060025B44209D06268206808EB0501BD +:10182000FFF738FC636808341D44F3E7294638465F +:10183000FFF7CAFF284604B0BDE8F081F8B50546B9 +:101840000C300F46FFF744FF05F10806044630460A +:10185000FFF73EFFA042304688BF6C68FFF738FFB5 +:10186000201A386020B130462C68FFF731FF204441 +:10187000F8BD000073B5144606460D46FFF72EFF6F +:10188000844228BF04460190DCB101A93046FFF72D +:10189000D5FF019B33B93268C5E90233C5E900249D +:1018A00001200CE09C4238BF0194286001986860D8 +:1018B0008442F5D93368AB60241AEC60022002B090 +:1018C00070BD2046FBE700002DE9FF410F46694649 +:1018D000FFF7D0FF6C4600B204EBC0050026AC4217 +:1018E00009D0D4F8048054F8081BB8194246FFF711 +:1018F000D1FB4644F3E7304604B0BDE8F081000078 +:1019000038B50546FFF7E0FF044601462846FFF7D5 +:1019100019FF204638BD00007047000010B4134680 +:10192000026814680022A4465DF8044B604700007A +:1019300000F5805090F859047047000000F5805081 +:1019400090F852047047000000F5805090F9580458 +:101950007047000050207047302383F3118800F552 +:101960008052D2F89C34D2F898041844D2F89434B7 +:101970001844D2F87C341844D2F88C341844D2F885 +:1019800088341844002383F31188704700F5805091 +:10199000C0F854140120704738B5C26A936923F027 +:1019A00001039361044600F0D5FE0546E36A9B6996 +:1019B000DB0706D500F0CEFE431BFA2BF6D900203C +:1019C00004E004F58054012084F8520438BD00007E +:1019D0002DE9F04F0C4600F5805185B01F4691F877 +:1019E0005234BDF83890054690469BB1D1F8783412 +:1019F0000133C1F878342368980006D4237B082B80 +:101A00000BD9627B0AB10F2B07D9D1F87C34013393 +:101A1000C1F87C344FF0FF3010E0302383F311889D +:101A2000EB6AD3F8C42012F4001B0AD0D1F880343A +:101A30000133C1F88034002080F3118805B0BDE87F +:101A4000F08FD3F8C4302068C3F3014A6B6A482290 +:101A5000002812FB0A33B4BF40F0804080041860B5 +:101A60002268520044BF40F000501860207B4FEACB +:101A70000A6242EA00425A60607B4FEA4A1610B39B +:101A800042F440125A60D1F8B0240132C1F8B024B7 +:101A9000AA1902F58352117B41F020011173207BBA +:101AA000039300F0B3FE039B033080105FFA8BF2C8 +:101AB00082420BF1010B0DDA04EB820103EB82028F +:101AC00049689160F2E7AA1902F58352117B60F32D +:101AD0004511E3E7EB6A012202FA0AF2C3F8CC20CF +:101AE00005EB4A11AB1903F5825301F58251C3E9A5 +:101AF00004871831234604F10C0253F8040B41F813 +:101B0000040B9342F9D11B880B802E4441F26803E9 +:101B100046F803A006F5805609F0030396F86C20FA +:101B200043F0100322F01F02134386F86C300023A9 +:101B300083F31188CDF8009042463B462146284663 +:101B400000F02AFE012079E713B500F580540191D9 +:101B5000606CFFF7DDFD1F280AD90199606C202217 +:101B6000FFF74CFEA0F120035842584102B010BDCF +:101B70000020FBE708B5302383F3118800F580507F +:101B8000406CFFF799FD002383F3118808BD000026 +:101B900000220260828142608260704710B500229C +:101BA0000023C0E900230023044603810C30FFF723 +:101BB000EFFF204610BD00002DE9F0479A4688B09F +:101BC000074688469146302383F3118807F58054F1 +:101BD0006846FFF7E3FF606CFFF780FD1F282DD9F3 +:101BE000606C20226946FFF78BFE202826D194F8EE +:101BF00052341BB303AD444605AB2E4603CE9E4282 +:101C000020606160354604F10804F6D13068206038 +:101C1000B388A380DDE90023C9E90023BDF80830BB +:101C2000AAF80030002383F3118853464A46414600 +:101C3000384608B0BDE8F04700F09CBD002080F3B6 +:101C4000118808B0BDE8F0872DE9F84F002306465B +:101C5000C0E90133294B46F8303B00F58154054675 +:101C600088463746103438462037FFF797FFA7429B +:101C7000F9D105F580544FF4805326630026C4E95A +:101C80000D366764012305F5835705F5A359E6630F +:101C900084F8403084F84830103709F110094FF0CB +:101CA000000A4FF0000B47E908ABA7F11800FFF757 +:101CB0006FFF203747F8286C4F45F4D1B8F1010F7A +:101CC00084F85884A4F85A64A4F85C64A4F85E64A8 +:101CD00084F86064A4F86264A4F86464A4F8666498 +:101CE00084F8686402D9064800F02EFD054B53F8CD +:101CF0002830EB622846BDE8F88F00BF9448000802 +:101D0000684800088448000810B5044B1978044658 +:101D10004A1C1A70FFF798FF204610BDF1620020A0 +:101D20002DE9F84315460C4600295CD0022001F04D +:101D300073FE2E49B0FBF4F78C428CBF0A211121AF +:101D40004B1EB7FBF1F601FB1671DAB221B1022B83 +:101D50001946F5D8002032E0731EB3F5806FF9D232 +:101D6000C2EBC20808F103014FEAE10EC1F3C7015B +:101D7000A2EB010C0EF101094FF47A735FFA8CF7B4 +:101D80000EFB033E59FA8CFCBEFBFCFCBCF5617FEC +:101D900017DC1FFA8CF34A1C57FA82F27243B0FB2D +:101DA000F2F08442D6D14A1E0F2AD3D87A1E072ACF +:101DB000D0D801202B806E8028716971AF71BDE889 +:101DC000F88308F1FF314FEAE10CC1F3C701521A61 +:101DD0000CF1010ED7B20CFB03335EFA82F2B3FBB7 +:101DE000F2F39BB2D7E70846E9E700BF3F420F0096 +:101DF00030B50D4B0D4D05201C786C438C420ED137 +:101E00005978518099785171D978917119791171F6 +:101E10005B7903EB83035B001380012030BD013845 +:101E200003F10603E8D1F9E7D448000840420F0067 +:101E300038B500F58053114A93F85834D55C4FF407 +:101E40005472554305F1804303F5244304460021B1 +:101E50001846FFF731F90A4B60612B44A361094B27 +:101E60002B44E361084B2B442362084B2B446362F1 +:101E7000E36A0022C3F8C02038BD00BF7C480008D8 +:101E800070A40040B0A4004088A5004078A600409F +:101E90002DE9F04F00F580551F4695F85834022B78 +:101EA00089B004468946904604D90026304609B0D8 +:101EB000BDE8F08FA64A52F8231009B942F8230072 +:101EC000A448C4F80C900178277499B9302383F39F +:101ED0001188A14B9A6D42F000729A659A6B42F09C +:101EE00000729A639A6B22F000729A630123037066 +:101EF00081F3118895F85134CBB9302383F31188DD +:101F0000964A95F85834D35C012B2AD0022B2FD057 +:101F10003BB90321152001F093FE0321162001F0A7 +:101F20008FFE012385F85134002383F31188302379 +:101F300083F31188E26A936923F01003936100F040 +:101F400009FC8246E36A9E6916F0080617D000F085 +:101F500001FCA0EB0A03FA2BF4D9002686F31188C2 +:101F6000A4E70321562001F06BFE03215720D6E79A +:101F70000321582001F064FE03215920CFE79A691C +:101F800042F001029A6100F0E5FB8246E36A9A6939 +:101F9000D00706D400F0DEFBA0EB0A03FA2BF5D93C +:101FA000DBE79A6942F002029A61E36A4FF0000AA5 +:101FB000C3F854A08AF31188686CFFF77DFB04F521 +:101FC000825B0BF1100B202200216846FFF774F8AA +:101FD00002A8FFF7DDFDCDF818A06A460BEB06035B +:101FE0000DF1180E9446BCE80300F44518605960E2 +:101FF000624603F10803F5D1DCF8000018602036D2 +:102000009CF804201A71B6F5806FDCD1002304F52A +:10201000A25285F8503485F853341A324946204686 +:10202000FFF77EFE064690B9E26A936923F001034A +:10203000936100F08FFB0546E36A9B69D9077FF542 +:1020400034AF00F087FB431BFA2BF5D92DE795F849 +:102050005E34C5F86C94591E95F85F34E26A013B12 +:102060001B0243EA416395F8601401390B43B5F84C +:102070005C14013943EA0143D361B8F1000F36D053 +:1020800004F5A352023241462046FFF7B1FE90B953 +:10209000E26A936923F00103936100F05BFB05465C +:1020A000E36A9B69DA077FF500AF00F053FB431B3F +:1020B000FA2BF5D9F9E695F86724C5F87084511E16 +:1020C00095F86824E36A013A120142EA012295F880 +:1020D000661401390A43B5F86414013942EA014231 +:1020E00042F40002DA60E36A4FF420629A64204608 +:1020F000FFF79EFE002385F85934E36A6FF04042F3 +:102100001A65E36A164A5A65E36A44229A65E36AE5 +:102110000722C3F8DC20E36A03229742DA653FF422 +:10212000C5AEE26A936923F00103936100F012FBEC +:102130000746E36A9B69DB0705D500F00BFBC31B71 +:10214000FA2BF6D9B1E6012385F85234AEE600BF8A +:10215000E8620020F0620020001002407C48000885 +:102160009B0008002DE9F04F054689B0904699463E +:10217000002741F2680A00F58056EB6AD3F8D430A4 +:10218000FB40D80751D505EB471252444FEA471B95 +:102190001379190749D4D6F884340133C6F8843446 +:1021A00005F5A553C3E9008913799A0648BFD6F807 +:1021B000B43405EB0B0248BF0133524448BFC6F8A4 +:1021C000B434137943F008031371DB0722D596F872 +:1021D0005334FBB105F58254183468465C44FFF76C +:1021E000DDFC03AB04F1080C206861681A4603C2E9 +:1021F000083464451346F7D120681060A2889A809D +:102200000123ADF808302B68CDE90089DB6B694606 +:1022100028469847D6F8A834D6F854040133C6F8AF +:10222000A83410B103681B6998470137202FA4D147 +:1022300009B0BDE8F08F00002DE9F04F8DB00446E5 +:102240000F4600F089FA82468946002F56D1E36A8C +:10225000D3F89020920141BF04F58051D1F8982421 +:102260000132C1F89824D3F89020160703D100203A +:102270000DB0BDE8F08FD3F89050E669C5F30125A5 +:10228000482303FB0566E8464046FFF781FC3268B9 +:1022900051004ABF22F06043C2F38A4343F0004337 +:1022A000920048BF43F080430093736813F4001317 +:1022B0001FBF04F5805201238DF80D30D2F8B834D9 +:1022C0000EBF8DF80D300133C2F8B834F38803F037 +:1022D0000F038DF80C304FF0000B9DF80C0000F050 +:1022E00095FA5FFA8BF3984220D9F2180CA90B44A7 +:1022F000127A03F82C2C0BF1010BEEE7012FB6D16B +:10230000E36AD3F89820950141BF04F58051D1F8D4 +:1023100098240132C1F89824D3F898201007A6D049 +:10232000D3F89850266AC5F30125A9E7EFB9E36A07 +:10233000C3F8945004A8FFF731FC98E80F0007ADEC +:1023400007C52B800023ADF8183023682046CDE95F +:1023500004A9DB6B04A9984704F5805458B1D4F85C +:1023600090340133C4F8903482E7012F04BFE36A4C +:10237000C3F89C50DEE7D4F894340133C4F89434A5 +:10238000012075E72DE9F04105460F4600F5805420 +:10239000012639462846FFF74FFF10B184F85364F1 +:1023A000F7E7D4F8A834D4F854040133C4F8A834B7 +:1023B00020B10368BDE8F0411B691847BDE8F08112 +:1023C000F0B5C36A1A6C12F47F0F2BD000F580545D +:1023D0001B6CC4F8AC3441F26805002347194FF078 +:1023E000010C00EB43122A445E01117911F0020F37 +:1023F00015D0490713D4B959C66AD6F8C8E00CFA03 +:1024000001F111EA0E0F0AD0C6F8D010117941F08F +:1024100004011171D4F88C240132C4F88C240133E6 +:10242000202BDED1F0BD00002B4B70B51E561B5C7F +:10243000012B2FD8294D2A4A55F8233052F826402F +:102440000BB341B3236D1A060FD58023236500F02B +:1024500083F950EA01020B4602D0013861F1000312 +:10246000024655F82600FFF77DFE236D1B032CD591 +:1024700055F826304FF4002203F5805322650122DF +:1024800083F8592421E001232365082323654FF4B1 +:102490008063236570BD236DDA0702D4236D9B072B +:1024A00006D5032355F8260023650021FFF76AFFB0 +:1024B000236D180702D4236DD90606D5182355F8C5 +:1024C000260023650121FFF75DFF55F82600BDE8D2 +:1024D0007040FFF775BF00BF80480008E862002029 +:1024E0008448000808B5302383F31188FFF768FF9C +:1024F000002383F3118808BDC36AD3F8C40080F4B5 +:102500000010C0F34050704708B5302383F31188A2 +:1025100000F58050406CFFF7E1F8002383F3118849 +:1025200043090CBF0120002008BD000000F58053C6 +:1025300093F8592462B1C16A8A6922F001028A6162 +:10254000D3F89C240132C3F89C24002283F8592438 +:10255000704700002DE9F743302181F3118800F521 +:1025600082511031002541F2680E4FF0010800F54C +:10257000805C00EB45147444267977071CD4F6067A +:102580001AD5D0F82C908E69D9F8C87008FA06F6DA +:102590003E4211D04F6801970F689742019F9F41BB +:1025A0000AD2C9F8D060267946F004062671DCF814 +:1025B00088440134CCF888440135202D01F12001F4 +:1025C000D7D1002383F3118803B0BDE8F083000066 +:1025D000F8B51E46002313700F4605461446FFF754 +:1025E00093FF80F0010038701EB12846FFF784FF8A +:1025F0002070F8BD2DE9F04F85B09946DDE90EA3B6 +:102600000D4602931378019391F800B08046164668 +:1026100000F0A2F82B7804460F4613B93378002B4C +:1026200041D022463B464046FFF794FFFFF75AFF52 +:10263000FFF77CFF4B4632462946FFF7C9FF2B7850 +:1026400033B1BBF1000F03D0012005B0BDE8F08F1E +:10265000337813B1019B002BF6D108F58053039317 +:10266000029B544577EB03031DD2039BD3F854041C +:10267000C8B10368AAEB04011B6898474B46324671 +:1026800029464046FFF7A4FF2B7813B1BBF1000F9A +:10269000DAD1337813B1019B002BD5D100F05CF86F +:1026A00004460F46DCE70020CFE7000008B5002114 +:1026B0000846FFF7B9FEBDE8084001F06DB800001C +:1026C00008B501210020FFF7AFFEBDE8084001F08A +:1026D00063B8000008B500210120FFF7A5FEBDE8A2 +:1026E000084001F059B8000008B501210846FFF77D +:1026F0009BFEBDE8084001F04FB8000000B59BB05C +:10270000EFF3098168226846FEF7C4FCEFF3058306 +:10271000014B9B6BFEE700BF00ED00E008B5FFF743 +:10272000EDFF000000B59BB0EFF309816822684619 +:10273000FEF7B0FCEFF30583014B5B6BFEE700BFD8 +:1027400000ED00E0FEE700000FB408B5029801F0CC +:102750002BFBFEE701F014BE01F0F6BD13B56C468D +:1027600084E80600031D94E8030083E805000120C7 +:1027700002B010BD73B58568019155B11B885B0728 +:1027800007D4D0E900369B6B9847019AC1B2304616 +:10279000A847012002B070BDF0B5866889B0054633 +:1027A0000C465EB1BDF838305B070AD4D0E900377B +:1027B0009B6B98472246C1B23846B047012009B00A +:1027C000F0BD00220023CDE900230023ADF808303E +:1027D0000A4603AB01F10806106851681C4603C4A1 +:1027E0000832B2422346F7D1106820609288A28056 +:1027F000FFF7B2FF0423ADF808302B68CDE90001E4 +:10280000DB6B694628469847D8E70000082817D9A7 +:1028100009280CD00A280CD00B280CD00C280CD07E +:102820000D280CD00E2814BF4020302070470C20FB +:1028300070471020704714207047182070472020E0 +:10284000704700002DE9F041456A15B94162BDE8C5 +:10285000F0814B6823F06047C3F38A464FEAD37E8A +:10286000C3F3807816EA230638BF3E46AC462B46B3 +:102870005A68BEEBD27F22F060440AD0002A18DAF0 +:10288000A40CB44217D19D420FD10D60DEE7134670 +:10289000EEE7A74207D102F08044C2F380724245BE +:1028A0000BD054B1EFE708D2EDE7CCF800100B6085 +:1028B000CDE7B44201D0B442E5D81A689C46002A5C +:1028C000E5D11960C3E700002DE9F047089D01F04C +:1028D00007044FEAD508224405F0070500EBD100B4 +:1028E0004FF47F49944201D1BDE8F08704F0070717 +:1028F00005F0070A57453E4638BF5646C6F108065A +:10290000111B8E4228BF0E46E10808EBD50E415C34 +:1029100013F80EC0B94029FA06F721FA0AF1FFB2FE +:102920008CEA010147FA0AF739408CEA010C03F8F6 +:102930000EC034443544D5E780EA0120082341F233 +:10294000210201B24000002980B203F1FF33B8BF79 +:10295000504013F0FF03F4D17047000038B50C4627 +:102960008D18A54200D138BD14F8011BFFF7E4FF14 +:10297000F7E7000042684AB11368436043898189E0 +:1029800001339BB29942438138BF8381104670471F +:1029900070B588B0202204460D4668460021FEF737 +:1029A0008BFB20460495FFF7E5FF024658B16B46C6 +:1029B000054608AE1C4603CCB44228606960234635 +:1029C00005F10805F6D1104608B070BD082817D9E2 +:1029D00009280CD00A280CD00B280CD00C280CD0BD +:1029E0000D280CD00E2814BF4020302070470C203A +:1029F000704710207047142070471820704720201F +:102A000070470000082817D90C280CD910280CD9B9 +:102A100014280CD918280CD920280CD930288CBFA0 +:102A20000F200E207047092070470A2070470B20A6 +:102A300070470C2070470D20704700002DE9F843C7 +:102A4000078C072F04461ED9D0E9029800254FF6BF +:102A5000FF73C5F12006A5F1200029FA05F108FA57 +:102A600006F628FA00F031430143C9B21846FFF7D1 +:102A700063FF0835402D0346EBD1E1693A46BDE8D6 +:102A8000F843FFF76BBF4FF6FF70BDE8F883000017 +:102A900010B54B6823B9CA8A63F30902CA8210BD14 +:102AA00004691A681C600361C38A013BC3824A60DF +:102AB000EFE700002DE9F84F1D46CB8A0F46C3F320 +:102AC00009010529814692460B4630D00020AAB262 +:102AD00007F11A049EB2042E1FFA80F80FD8904511 +:102AE00003F1010306D3FB8A0A4462F30903FB8264 +:102AF00001201AE01AF80060E6540130EAE7904538 +:102B0000F1D2A1F1050B1C237C68BBFBF3F203FBA4 +:102B100012BB1FFA8BF6002C45D14846FFF72AFF5F +:102B2000044638B978606FF00200BDE8F88F4FF0C6 +:102B30000008E6E7002606607860ADB24FF0000BB3 +:102B4000454510D90AEB0803221D13F8011B9155C6 +:102B5000B1B208F101081B291FFA88F82BD04545AE +:102B600006F10106F1D8FB8AC3F30902154465F3A7 +:102B70000903BCE7013292B21C462368002BF9D14D +:102B80006B1F0B441C21B3FBF1F301339BB29A4240 +:102B9000D3D2BBF1000FD0D14846FFF7EBFE20B9EE +:102BA000C4F800B0BFE70122E7E7C0F800B05E4616 +:102BB00020600446C1E74545D5D94846FFF7DAFE0F +:102BC00008B92060AFE7C0F800B0002620600446D6 +:102BD000B6E700002DE9F04F2DED028B1C4683B0C7 +:102BE0005B69019207468846002B00F09A80238C8F +:102BF0002BB1E269002A00F09480072B35D807F149 +:102C00000C00FFF7B7FE054638B96FF002052846FD +:102C100003B0BDEC028BBDE8F08F14220021FEF75B +:102C20004BFA228CE16905F10800FEF733FA208C9B +:102C3000013080B2FFF7E6FEFFF7C8FE013880B230 +:102C40002084013028746369228C1B782A4403F0A5 +:102C50001F0363F03F0348F0004113723846696078 +:102C60002946FFF7EFFD0125D1E700F10C034FF0F6 +:102C7000000908EE103A4FF0800A4E464D4618EE15 +:102C8000100AFFF777FE83460028BED014220021E9 +:102C9000FEF712FA002E3AD1019BABF8083002225F +:102CA0000BF1080E1FFA82FC0CF10100BCF1060FBB +:102CB000218C80B201D88E422BD3FFF7A3FEFFF701 +:102CC00085FE62691278013802F01F028E4208BF49 +:102CD0004FF0400A42EA49121BFA80F14AEA020A1E +:102CE000013048F0004281F808A08BF81000CBF8C2 +:102CF000042059463846FFF7A5FD238C0135B34221 +:102D00002DB289F001094FF0000AB8D17FE7002207 +:102D1000C6E7E169895D0EF802100136B6B20132EC +:102D2000C0E76FF0010572E7F8B515460E46302290 +:102D3000002104461F46FEF7BFF9069B6360B5F508 +:102D4000001F079BA76034BF6A094FF6FF72A3629A +:102D500097B2E66104F1100000239A4206D80023DE +:102D60000360A782E3822383E360F8BD066001333A +:102D700030462036F1E7000003781BB94BB2002B38 +:102D8000C8BF01707047000000787047F8B50C4666 +:102D9000C969074611B9238C002B37D1257E1F2D19 +:102DA00034D8387828BB228C072A2CD8268A36F0CB +:102DB00003032BD14FF6FF70FFF7D0FD20F0010089 +:102DC0003102400441EA0561400C41EA40254FF6DA +:102DD000FF72234629463846FFF7FCFE002807DD30 +:102DE000626913780133DBB21F2B88BF0023137095 +:102DF000F8BD218A2D0645EA012505432046FFF747 +:102E00001DFE0246E5E76FF00300F1E76FF00100F9 +:102E1000EEE7000070B58AB004461646002128226D +:102E200068461D46FEF748F9BDF83830ADF8103059 +:102E30000F9B05939DF840308DF81830119B079338 +:102E40006946BDF84830ADF820302046CDE902652E +:102E5000FFF79CFF0AB070BD2DE9F041D36905462C +:102E60000C4616460BB9138C5BBB377E1F2F28D838 +:102E700095F80080B8F1000F26D03046FFF7DEFD50 +:102E80003378210241EAC33141EA0801338A41EA39 +:102E9000076141EA03410246334641F0800128467A +:102EA000FFF798FE00280ADD3378012B07D17269FD +:102EB00013780133DBB21F2B88BF00231370BDE8EA +:102EC000F0816FF00100FAE76FF00300F7E7000010 +:102ED000F0B58BB004460D461746002128226846FF +:102EE0001E46FEF7E9F89DF84C305A1E53425341F6 +:102EF0008DF800309DF84030ADF81030119B0593EF +:102F00009DF848308DF81830149B07936A46BDF839 +:102F10005430ADF8203029462046CDE90276FFF73F +:102F20009BFF0BB0F0BD0000406A00B10430704759 +:102F3000436A1A68426202691A600361C38A013BEC +:102F4000C38270472DE9F041D0F82080194E144615 +:102F50001D464146002709B9BDE8F081D1E90223A9 +:102F6000A21A65EB0303964277EB03031ED2036AB2 +:102F70008B420DD1FFF78CFD036A1B680362036966 +:102F80000B60C38A0161016A013BC3828846E2E7A4 +:102F9000FFF77EFD0B68C8F8003003690B60C38A39 +:102FA0000161013BC382D8F80010D4E78846096864 +:102FB000D1E700BF80841E002DE9F04F8BB00D4695 +:102FC000DDF8509014469B468046002800F0198199 +:102FD000B9F1000F00F01581531E3F2B00F2118153 +:102FE000012A03D1BBF1000F40F00B810023CDE992 +:102FF0000833B8F81430B5EBC30F4FEAC30703D357 +:1030000000200BB0BDE8F08F2B199F42D8F80C3090 +:103010003ABF7F1BFFB227461BB9D8F81030002BF0 +:103020007AD0272D4ED8C5F12806B7424FF00003BD +:103030002CBFF6B23E4600932946D8F8080008ABEC +:103040003246FFF741FCA7EB060A35445FFA8AFADD +:10305000B8F8143003F10053053BDB000493D8F8B3 +:103060000C3003932821039B13B1BAF1000F2CD12C +:10307000D8F8100040B1BAF1000F05D0009608ABA7 +:103080005246691AFFF720FC38B2002FB8D0660705 +:103090000AD00AAB03EBD401624211F8083C02F0FB +:1030A0000702134101F8083C082C3CD9102C40F2CF +:1030B000B580202C40F2B780BBF1000F00F09C805F +:1030C000082334E0BA460026C2E7049BE02B28BF61 +:1030D000E02306930B44AB42059314D95A1B039883 +:1030E0000096924534BF5246D2B2691A08AB0430FA +:1030F0000792FFF7E9FB079A1644AAEB020A154468 +:10310000F6B25FFA8AFA049B069A05999B1A049311 +:10311000039B1B680393A6E70093D8F8080008AB4D +:103120003A462946AEE7BBF1000F13D00123B4EBBA +:10313000C30F6CD0082C12D89DF82030621E23FAE1 +:1031400002F2D50706D54FF0FF3202FA04F423430A +:103150008DF820309DF8203089F8003051E7102C90 +:1031600012D8BDF82030621E23FA02F2D10706D52C +:103170004FF0FF3202FA04F42343ADF82030BDF8DB +:103180002030A9F800303CE7202C0FD80899631EA6 +:1031900021FA03F3DA0705D54FF0FF3202FA04F4FF +:1031A0000C430894089BC9F800302AE7402C2BD028 +:1031B000DDE90865611EC4F12102A4F1210326FAAC +:1031C00001F105FA02F225FA03F311431943CB0783 +:1031D00012D50122A4F12003C4F1200102FA03F365 +:1031E00022FA01F1A240524243EA010363EB430396 +:1031F00032432B43CDE90823DDE90823C9E9002345 +:10320000FFE66FF00100FCE66FF00800F9E6082C1D +:10321000A0D9102CB3D9202CEED8C3E7BBF1000FF6 +:10322000ADD0022383E7BBF1000FBBD004237EE7C0 +:1032300030B5012A144638BF0124402C85B028BF80 +:1032400040240025012ACDE9025518D81B788DF8B5 +:10325000083063070AD004AB03EBD405624215F8CB +:10326000083C02F00702934005F8083C0091034631 +:103270002246002102A8FFF727FB05B030BD082A2F +:10328000E4D9102A03D81B88ADF80830E1E7202ADA +:103290008DBFD3E900231B680293CDE90223D8E751 +:1032A00010B5CB681BB98B600B618B8210BD0469B4 +:1032B0001A681C600361C38A013BC382CA60F0E7DD +:1032C00003064CBFC0F3C0300220704708B5024669 +:1032D000FFF7F6FF022806D15306C2F30F2001D1F3 +:1032E00000F0030008BDC2F30740FBE72DE9F04FF3 +:1032F00093B0CDE903230A6804461046FFF7E0FFC8 +:10330000022814BFC2F306260026002A0D46824674 +:1033100080F2F78112F0C04940F0F381097B002967 +:1033200000F0EF81022803D02378B34240F0EC8113 +:10333000C2F304630693104602F07F030593FFF780 +:10334000C5FF059B29444FEA834848EA0A4848EAF2 +:103350004668CE7800230022CDE90823F30983468E +:1033600048EA0008029367D0059B0093024667680D +:10337000534608A92046B847002800F0C881276AAC +:103380004FB9414604F10C00FFF702FB074690B924 +:103390006FF0020054E03B6998450DD03F68002F64 +:1033A000F9D1414604F10C00FFF7F2FA0746002874 +:1033B000EED0236A3B60276297F817C006F01F081B +:1033C000CCF3840CACEB08001FFA80FE0028B8BFD9 +:1033D0000EF12000A8EB0C031FFA83FED7E90221AF +:1033E000B8BF00B2002B0793BEBF0EF120031BB283 +:1033F000079352EA010338D0039BDFF824E39A1ABB +:10340000049B4FF0000C63EB010196457CEB01033C +:103410002BD36B7B97F81AE0734519D1029B002BD5 +:1034200078D0012821DC7868F8B9DFF8F0C294453B +:1034300070EB010316D337E0276A27B96FF00C0051 +:1034400013B0BDE8F08F3B699845B5D03F68F4E70D +:10345000B24890427CEB010301D30020F0E7029BCD +:10346000002BFAD0079B0F2B17DCFA7DB30002F07C +:10347000030203F07C031343FB7539462046FFF734 +:1034800007FB6B7BBB76029B3BB9FB7DC3F38402DE +:10349000013262F38603FB75D0E76A7BBB7E9A42FA +:1034A000DBD1029B002B35D0B309022B32D0039B1A +:1034B000BB60049BFB60142200210DA8FDF7FCFDFE +:1034C000039B0A93049B0B932B1D0C932B7BADF852 +:1034D0003EB0013BDBB2ADF83C30069B8DF842308C +:1034E000059B8DF8433094F82C308DF840A083F084 +:1034F00001038DF844308DF84180A3680AA9204665 +:103500009847FB7DC3F38403013303F01F039B0241 +:10351000FB82A2E7FB7DC6F34012B2EBD31F40F063 +:10352000F980C3F38403434540F0FC80029A2B7B6F +:10353000B609002A52D016F0010661D1032B40F2E1 +:10354000F480039BBB60049BFB60FB8A66F309036A +:10355000FB822B7BAE1D033BDBB23246394604F1C6 +:103560000C00FFF7A7FA00280CDA39462046FFF7CF +:103570008FFAFB7DC3F38403013303F01F039B0227 +:10358000FB8205E7DDE90884AB883B834FF6FF73D8 +:10359000C9F12000A9F1200228FA09F104FA00F08B +:1035A000014324FA02F211431846C9B2FFF7C4F9E5 +:1035B00009F10809B9F1400F0346E9D1B8822A7B25 +:1035C000033AD2B23146FFF7C9F9FB7DB882DA433C +:1035D000C2F3C01262F3C713FB753EE786B92E1D16 +:1035E000013BDBB23246394604F10C00FFF762FAC8 +:1035F0000028BADB2A7BB88A013AD2B23146E2E728 +:10360000F98AC1F30901013B0429DAB25BD8281D0C +:10361000002307F11B069A4208D910F801CB06F8DF +:1036200001C0013101330529DBB2F4D103990A91BC +:1036300004990B91934207F11B010C9138BF04339D +:1036400079680D9134BF55FA83F300230E93FB8AFA +:10365000ADF83EB0C3F309031A44069B8DF842301F +:10366000059B8DF8433094F82C30ADF83C2083F066 +:1036700001038DF8443000238DF840A08DF841807F +:103680007B602A7BB88A013A291DFFF767F93B8BDB +:10369000B882834203D1A3680AA9204698472046EE +:1036A0000AA9FFF7FDFDFB7DBA8AC3F3840301334A +:1036B00003F01F039B02FB823B8B9A420CBF00204E +:1036C0006FF01000BCE67B68002BAFD0052001E056 +:1036D0001C3033461E68002EFAD1091A081D2E1D13 +:1036E000184401EB090CBCF11B0F5FFA89F39DD85C +:1036F0009A429BD916F8013B00F8013B09F10109F8 +:10370000EFE76FF009009BE66FF00A0098E66FF0B4 +:103710000B0095E66FF00D0092E600BF40420F00EF +:1037200080841E006FF00E008AE66FF00F0087E6BF +:10373000EFF3098305494A6B22F001024A636833BB +:1037400083F30988002383F31188704700EF00E0BA +:10375000302080F3118862B60C4B0D4AD96821F4F1 +:10376000E0610904090C0A43DA60D3F8FC20094936 +:1037700042F08072C3F8FC200A6842F001020A603D +:103780002022DA7783F82200704700BF00ED00E0C6 +:103790000003FA05001000E010B5302383F3118810 +:1037A0000E4B5B6813F4006314D0F1EE103AEFF3A4 +:1037B0000984683C4FF08073E361094BDB6B23663F +:1037C00084F3098800F0BAFA10B1064BA36110BD6A +:1037D000054BFBE783F31188F9E700BF00ED00E03C +:1037E00000EF00E03F03000842030008434B4FF4A2 +:1037F000007270B51A605A6912F4C06FFBD1404B69 +:103800009A6802F00C02042A20D01A6842F48072EE +:103810001A601A685205FCD501229A609A6802F073 +:103820000C02042AFAD13749374A0A600A6812F0B2 +:103830000F02FBD1C3F8982063221A601A6896031E +:10384000FCD42E4A4FF48071C2F88010C468E5039E +:1038500006D51A6842F480321A601A689103FCD5C2 +:10386000C269D20709D5D3F8982042F00102C3F803 +:103870009820D3F898209607FBD54269DA6044F483 +:1038800080721A6004F0807111B11A689501FBD53D +:10389000996802691B4E22F0030501F003012943D8 +:1038A000996085693560316869400907FBD1134922 +:1038B00005680D6046684E608068C1F880006E043F +:1038C00017D448698505FCD4996802F0030021F0FB +:1038D00003010143996092009968514011F00C0F67 +:1038E000FAD1E2055EBF1A6822F480721A600020E5 +:1038F00070BD48698005FCD5E6E700BF0070004058 +:1039000000100240002002400006040008B500F04C +:1039100083F9BDE8084000F05BB9000010B5394CF0 +:103920003948A36A4FF0FF32A262A36A0023A36260 +:10393000A16AE16A61F07F01E162E16A01F07F0161 +:10394000E162E16A216B2263216B2363216BA16B2E +:10395000A263A16BA363A16BE16BE263E16BE36321 +:10396000E16B216C2264226C2364226C226E42F093 +:1039700001022266D4F8802022F00102C4F88020DF +:10398000D4F88020A26D42F08052A265A26F22F08E +:103990008052A267A26F1D4A4FF400419160D3602C +:1039A000136253629362D362136353639363D3636B +:1039B000136453649364D36413655365116841F4CD +:1039C00080711160D4F8902012F4407F1EBF4FF434 +:1039D0008032C4F89020C4F890300D4A0023A360D0 +:1039E000C4F88820C4F89C30FFF700FF10B10948E4 +:1039F00000F0DAF9D4F8903023F00323C4F89030C3 +:103A000010BD00BF00100240FC48000800700040DC +:103A100055010051F4480008014B53F8200070474D +:103A200018230020074A08B5536903F001035361C6 +:103A300023B1054A13680BB150689847BDE80840A8 +:103A4000FFF7AABE0004014084650020074A08B5BC +:103A5000536903F00203536123B1054A93680BB124 +:103A6000D0689847BDE80840FFF796BE00040140C3 +:103A700084650020074A08B5536903F004035361C5 +:103A800023B1054A13690BB150699847BDE8084056 +:103A9000FFF782BE0004014084650020074A08B594 +:103AA000536903F00803536123B1054A93690BB1CD +:103AB000D0699847BDE80840FFF76EBE000401409A +:103AC00084650020074A08B5536903F01003536169 +:103AD00023B1054A136A0BB1506A9847BDE8084004 +:103AE000FFF75ABE0004014084650020164B10B554 +:103AF0005C6904F478725A61A30604D5134A936A88 +:103B00000BB1D06A9847600604D5104A136B0BB10D +:103B1000506B9847210604D50C4A936B0BB1D06BC0 +:103B20009847E20504D5094A136C0BB1506C9847CD +:103B3000A30504D5054A936C0BB1D06C9847BDE83A +:103B40001040FFF729BE00BF00040140846500203B +:103B5000194B10B55C6904F47C425A61620504D5C6 +:103B6000164A136D0BB1506D9847230504D5134ABF +:103B7000936D0BB1D06D9847E00404D50F4A136ED6 +:103B80000BB1506E9847A10404D50C4A936E0BB14B +:103B9000D06E9847620404D5084A136F0BB1506F7A +:103BA0009847230404D5054A936F0BB1D06F98470B +:103BB000BDE81040FFF7F0BD00040140846500201F +:103BC00008B500F0FBFCBDE80840FFF7E5BD0000CC +:103BD000062108B5084600F033F80621072000F05A +:103BE0002FF80621082000F02BF80621092000F00C +:103BF00027F806210A2000F023F80621172000F0FC +:103C00001FF80621282000F01BF8BDE80840072116 +:103C10001C2000F015B800004FF0E0230022586887 +:103C20004FF0FF31930003F1604303F5614301322C +:103C30009042C3F88010C3F88011F3D2704700009F +:103C400000F1604303F561430901C9B283F8001331 +:103C5000012200F01F039A4043099B0003F16043D7 +:103C600003F56143C3F880211A6070470023037590 +:103C7000826803691B6899689142FBD25A680360A5 +:103C800042601060586070470023037582680369C2 +:103C90001B6899689142FBD85A68036042601060C3 +:103CA0005860704708B50846302383F311880B7DB0 +:103CB000032B05D0042B0DD02BB983F3118808BD3D +:103CC0008B6900221A604FF0FF338361FFF7CEFF4C +:103CD0000023F2E7D1E9003213605A60F3E70000F5 +:103CE000FFF7C4BF054BD9680875186802681A60E9 +:103CF000536001220275D860FCF70CBBF86200200B +:103D000030B50C4BDD684B1C87B004460FD02B46FA +:103D1000094A684600F02AF92046FFF7E3FF009BB6 +:103D200013B1684600F02CF9A86907B030BDFFF761 +:103D3000D9FFF9E7F8620020A53C0008044B1A6897 +:103D4000DB6890689B68984294BF00200120704710 +:103D5000F8620020084B10B51C68D86822681A6009 +:103D6000536001222275DC60FFF78EFF014620467A +:103D7000BDE81040FCF7CEBAF862002038B5074C19 +:103D800007490848012300252370656000F044FCC2 +:103D90000223237085F3118838BD00BF60650020C1 +:103DA00020490008F862002008B572B6044B186577 +:103DB00000F0B4FA00F064FB024B03221A70FEE735 +:103DC000F86200206065002000F010B98B600223CB +:103DD00008618B82084670478368A3F1840243F828 +:103DE000142C026943F8442C426943F8402C094AD8 +:103DF00043F8242CC26843F8182C022203F80C2C38 +:103E0000002203F80B2C044A43F8102CA3F12000E5 +:103E1000704700BF2D030008F862002008B5FFF7C7 +:103E2000DBFFBDE80840FFF75BBF0000024BDB682B +:103E300098610F20FFF756BFF8620020302383F30C +:103E40001188FFF7F3BF000008B50146302383F364 +:103E500011880820FFF754FF002383F3118808BD61 +:103E600010B503689C68A2420CD85C688A600B603D +:103E70004C602160596099688A1A9A604FF0FF334C +:103E8000836010BD1B68121BECE700000A2938BFD5 +:103E90000A2170B504460D460A26601900F0B6FBEB +:103EA00000F0A2FB041BA54203D8751C2E46044655 +:103EB000F3E70A2E04D9BDE87040012000F0ECBB06 +:103EC00070BD0000F8B5144B0D46D96103F1100127 +:103ED00041600A2A1969826038BF0A22016048607D +:103EE0001861A818144600F083FB0A2700F07CFB39 +:103EF000431BA342064606D37C1C281900F086FB10 +:103F000027463546F2E70A2F04D9BDE8F8400120DC +:103F100000F0C2BBF8BD00BFF8620020F8B506464D +:103F20000D4600F061FB0F4A134653F8107F9F4285 +:103F300006D12A4601463046BDE8F840FFF7C2BF29 +:103F4000D169BB68441A2C1928BF2C46A34202D958 +:103F50002946FFF79BFF224631460348BDE8F8405B +:103F6000FFF77EBFF86200200863002010B4C0E9AC +:103F7000032300235DF8044B4361FFF7CFBF00002C +:103F800010B5194C236998420DD0D0E900328168F0 +:103F900013605A609A680A449A60002303604FF0E5 +:103FA000FF33A36110BD2346026843F8102F53600E +:103FB0000022026022699A4203D1BDE8104000F05D +:103FC0001FBB936881680B44936000F00DFB22696E +:103FD000E1699268441AA242E4D91144BDE8104054 +:103FE000091AFFF753BF00BFF86200202DE9F04720 +:103FF000DFF8BC8008F110072C4ED8F8105000F004 +:10400000F3FAD8F81C40AA68031B9A423ED814441D +:10401000D5E900324FF00009C8F81C4013605A601F +:10402000C5F80090D8F81030B34201D100F0E8FA9A +:1040300089F31188D5E9033128469847302383F363 +:1040400011886B69002BD8D000F0CEFA6A69A0EB1A +:1040500004094A4582460DD2022000F01DFB0022D1 +:10406000D8F81030B34208D151462846BDE8F04791 +:10407000FFF728BF121A2244F2E712EB090938BFF2 +:104080004A4629463846FFF7EBFEB5E7D8F8103028 +:10409000B34208D01444211AC8F81C00A960BDE836 +:1040A000F047FFF7F3BEBDE8F08700BF08630020CC +:1040B000F862002038B500F097FA054AD2E90845C1 +:1040C000031B181945F10001C2E9080138BD00BF02 +:1040D000F862002000207047FEE7000070470000F3 +:1040E0004FF0FF3070470000BFF34F8F024A136953 +:1040F000DB03FCD4704700BF0020024008B5094B29 +:104100001B7873B9FFF7F0FF074B5A69002ABFBF4E +:10411000064A9A6002F188329A601A6822F4806234 +:104120001A6008BD78650020002002402301674521 +:1041300008B50B4B1B7893B9FFF7D6FF094B5A69AB +:1041400042F000425A611A6842F480521A601A68BA +:1041500022F480521A601A6842F480621A6008BD24 +:104160007865002000200240FF289ABF00F58030CB +:10417000C0020020704700004FF40060704700004C +:104180004FF4807070470000FF2808B50BD8FFF788 +:10419000EBFF00F500630268013204D10430834272 +:1041A000F9D1012008BD0020FCE70000FF2838B548 +:1041B000044624D8FFF798FFFFF7A0FF114AF32326 +:1041C000136102235361C3005169C50903F47E736F +:1041D00043EAC5230B435361536943F4803353616E +:1041E000FFF782FF4FF40061FFF7BEFF00F044F9D4 +:1041F000FFF79EFF2046BDE83840FFF7C5BF00200F +:1042000038BD00BF002002402DE9F84340EA020318 +:1042100013F00703144606D0304B40F247321A60C1 +:104220000020BDE8F88385182D4A95420CD92B4A09 +:104230004FF453711160F3E7031D1B684A68934202 +:1042400008D1083C08300831072C14D902680B68E3 +:104250009A42F1D0FFF752FFFFF746FF214E083197 +:104260004FF001084FF00009012CA1F1080706D812 +:10427000FFF75EFF01E0002CECD10120D1E7C6F88A +:104280001480054651F8083C45F8043B51F8043CBD +:104290004360FFF729FF336943F001033361C6F838 +:1042A0001490026851F8083C9A420CD00B4B4FF422 +:1042B0005D721A600C4B18600C4B1C600C4B1F603D +:1042C000FFF736FFACE72D6851F8043C9D4201F141 +:1042D0000801EBD1083C0830C6E700BF7465002038 +:1042E000000008080020024068650020706500207A +:1042F0006C650020084908B50B7828B11BB9FFF799 +:10430000FDFE01230B7008BD002BFCD0BDE808406A +:104310000870FFF70DBF00BF7865002008B506499B +:10432000064800F0ABF8BDE808404FF400414FF0FC +:10433000805000F0A3B800BF007F01000001002002 +:10434000084600F035BA000038B5EFF311859DB985 +:10435000EFF30584C4F30804302334B183F31188E8 +:10436000FFF7A8FE85F3118838BD83F31188FFF7A6 +:10437000A1FE84F3118838BDBDE83840FFF79ABE2E +:1043800038B5FFF7E1FF114C114AC00840EA41700F +:10439000A0FB025EC908A0FB040C1CEB050CA1FBF2 +:1043A00004404FF000035B41A1FB02121CEB040C24 +:1043B00043EB000011EB0E0142F10002411842F103 +:1043C0000000090941EA007038BD00BFCFF753E390 +:1043D000A59BC4200244D2B2904200D17047431C36 +:1043E000800000F1804000F51450006841F8040B93 +:1043F000D8B2F1E7124B10B5D3F89040240409D499 +:10440000D3F89040C3F89040D3F8904044F400446F +:10441000C3F890400B4C2368024443F4807323603C +:10442000D2B2904200D110BD431C800000F1804008 +:1044300000F5145051F8044B0460D8B2F1E700BF06 +:10444000001002400070004007B5012201A90020C1 +:10445000FFF7C0FF019803B05DF804FB13B50446F5 +:10446000FFF7F2FFA04205D0012201A9002001942C +:10447000FFF7C0FF02B010BD70470000704700009A +:1044800070470000074B45F255521A6002225A60ED +:1044900040F6FF729A604CF6CC421A60024B012241 +:1044A0001A7070470030004080650020034B1B7875 +:1044B0001BB1034B4AF6AA221A60704780650020A0 +:1044C00000300040054B1A6832B902F1804202F513 +:1044D0000432D2F894201A60704700BF7C65002037 +:1044E000024B4FF40002C3F89420704700100240C2 +:1044F00008B5FFF7E7FF024B1868C0F3407008BD2E +:104500007C65002070470000FEE700000A4B0B4866 +:104510000B4A90420BD30B4BDA1C121AC11E22F02D +:1045200003028B4238BF00220021FCF7C5BD53F8BF +:10453000041B40F8041BECE7A44A000804660020B2 +:1045400004660020046600200023054A1946013352 +:10455000102BC2E9001102F10802F8D1704700BF28 +:104560008465002008B5124B9A6D42F001029A65ED +:104570009A6F42F001029A670E4A9B6F936843F06C +:10458000010393600620FFF747FA0B4BB0FBF3F0F3 +:104590004FF080434FF0FF3201389862DA62002218 +:1045A0009A615A63DA605A6001225A611A6008BD42 +:1045B00000100240002004E040420F004FF0804213 +:1045C00008B51169D3680B40D9B2C9439B07116183 +:1045D00007D5302383F31188FFF7F6FB002383F31D +:1045E000118808BDFFF7BEBF4FF08043586A70477F +:1045F0004FF08043002258631A610222DA6070474C +:104600004FF080430022DA60704700004FF0804393 +:1046100058637047FEE7000070B51B4B016300252F +:10462000044686B0586085620E46FFF791F804F1A3 +:104630001003C4E904334FF0FF33C4E90635C4E97D +:104640000044A560E562FFF7CFFF2B460246C4E9B0 +:10465000082304F134010D4A256580232046FFF725 +:10466000B5FB0123E0600A4A03750092726801926B +:10467000B268CDE90223074B6846CDE90435FFF760 +:10468000CDFB06B070BD00BF606500202C4900085E +:104690003149000815460008024AD36A1843D0621F +:1046A000704700BFF86200204B6843608B688360EE +:1046B000CB68C3600B6943614B6903628B694362DA +:1046C0000B6803607047000008B5204BDA6A42F0BF +:1046D0007F02DA62DA6A22F07F02DA62DA6ADA6C80 +:1046E00042F07F02DA64DA6E42F07F02DA66184A3C +:1046F000DB6E11464FF09040FFF7D6FF02F11C0130 +:1047000000F58060FFF7D0FF02F1380100F580600E +:10471000FFF7CAFF02F1540100F58060FFF7C4FF04 +:1047200002F1700100F58060FFF7BEFF02F18C011D +:1047300000F58060FFF7B8FF02F1A80100F5806086 +:10474000FFF7B2FFBDE80840FFF7E8B800100240ED +:104750003849000808B500F009F8FFF70FFBBDE87D +:104760000840FFF7AFBE00007047000008B5FFF734 +:10477000CDF8FFF7E9FEFFF7F7FFBDE80840FFF7C8 +:1047800031BF00000B460146184600F003B8000098 +:1047900000F00EB810B5054C13462CB10A46014680 +:1047A0000220AFF3008010BD2046FCE700000000AF +:1047B000024B01461868FFF7C3BD00BF402300202D +:1047C00010B501390244904201D1002005E0037880 +:1047D00011F8014FA34201D0181B10BD0130F2E7C0 +:1047E0002DE9F041A3B1C91A17780144044603F139 +:1047F000FF3C8C42204601D9002009E00578BD42EB +:1048000004F10104F5D10CEB0405D618A54201D141 +:10481000BDE8F08115F8018D16F801EDF045F5D0F1 +:10482000E7E70000034611F8012B03F8012B002AEB +:10483000F9D170476F72672E6172647570696C6F21 +:10484000742E4D6174656B473437342D5065726931 +:104850007068000040A2E4F1646891060041A3E59D +:10486000F2656992070000004261642043414E49AD +:104870006661636520696E6465782E000001000042 +:104880000001FF00006400400068004000000000DC +:1048900000000000911E00081D190008F525000801 +:1048A0008D190008D1190008B91B000899190008D2 +:1048B000551900085919000831190008191900087C +:1048C000751B00083D1900085D27000849190008FC +:1048D000491B000801040E05054B02020E05054B9D +:1048E00004010E05054B05010B04044B08010603EA +:1048F00003460000636C6B737763000000030000E5 +:1049000000000000000100000000010103000000A1 +:104910000328310104070400010000006330000097 +:104920001C49000850630020606500206D61696EBD +:104930000069646C650000000000802A000000002F +:10494000AAAAAAAA00000024FFFF0000000000009D +:10495000009009000028000100000000AAAAAAAAED +:1049600000000001FFFF00000000900900000000AF +:104970000000001400000000AAAAAAAA000000106B +:10498000FFDF000000000000000000000000000049 +:1049900000000000AAAAAAAA00000000FFFF000071 +:1049A0000000000000000000000000000000000007 +:1049B000AAAAAAAA00000000FFFF00000000000051 +:1049C000000000000000000000000000AAAAAAAA3F +:1049D00000000000FFFF00000000000000000000D9 +:1049E0000000000000000000AAAAAAAA000000001F +:1049F000FFFF0000000000000000000000000000B9 +:104A00009204000000000000007007000000000099 +:104A1000FE2A0100D2040000006889096D8BB902EA +:104A200000B4C4040068890900688909006889091C +:104A30000068890900688909006889090000000088 +:104A400044230020000000000000000000000000DF +:104A50000000000000000000000000000000000056 +:104A60000000000000000000000000000000000046 +:104A70000000000000000000000000000000000036 +:104A80000000000000000000000000000000000026 +:104A90000000000000000000000000000000000016 +:044AA0000000000012 +:00000001FF diff --git a/Tools/bootloaders/MatekH7A3_bl.bin b/Tools/bootloaders/MatekH7A3_bl.bin index 81a83e580b27c..6b2d6edac8849 100755 Binary files a/Tools/bootloaders/MatekH7A3_bl.bin and b/Tools/bootloaders/MatekH7A3_bl.bin differ diff --git a/Tools/bootloaders/MatekH7A3_bl.hex b/Tools/bootloaders/MatekH7A3_bl.hex index e36bf98ed9b64..ce600d6df1f5d 100644 --- a/Tools/bootloaders/MatekH7A3_bl.hex +++ b/Tools/bootloaders/MatekH7A3_bl.hex @@ -1064,7 +1064,7 @@ :10426000C3F83C21D3F8642142F08042C3F86421B2 :10427000D3F86431704700BF0080005100440258F9 :104280000048025800C000F0020000010000FF01D9 -:1042900000828402424040001703010163020103CF +:10429000008284028280800017030101630201030F :1042A0005505FF01000001200210F000004101202F :1042B000002000524FF0B04208B5D2F8883003F029 :1042C0000103C2F8883023B1044A13680BB1506867 diff --git a/Tools/bootloaders/MatekL431-APDTelem_bl.bin b/Tools/bootloaders/MatekL431-APDTelem_bl.bin new file mode 100755 index 0000000000000..293ca93fee825 Binary files /dev/null and b/Tools/bootloaders/MatekL431-APDTelem_bl.bin differ diff --git a/Tools/bootloaders/MicoAir743_bl.bin b/Tools/bootloaders/MicoAir743_bl.bin new file mode 100644 index 0000000000000..e4880f850cd33 Binary files /dev/null and b/Tools/bootloaders/MicoAir743_bl.bin differ diff --git a/Tools/bootloaders/MicoAir743_bl.hex b/Tools/bootloaders/MicoAir743_bl.hex new file mode 100644 index 0000000000000..36b22e6b3a83c --- /dev/null +++ b/Tools/bootloaders/MicoAir743_bl.hex @@ -0,0 +1,1213 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008F12E0008E2 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E30200085D4400088944000848 +:10006000B5440008E14400080D45000845110008AA +:100070006D11000899110008C5110008F111000860 +:100080001912000845120008E3020008E302000804 +:10009000E3020008E3020008E30200083945000813 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E302000811460008E3020008E3020008FA +:1000E0009D450008E3020008E3020008E30200085F +:1000F000E3020008E3020008E302000871120008AE +:10010000E3020008E302000825460008E3020008B5 +:10011000E3020008E3020008E3020008E30200082B +:100120009D120008C5120008F11200081D130008F6 +:1001300049130008E3020008E3020008E302000894 +:10014000E3020008E3020008E3020008E3020008FB +:10015000711300089D130008C9130008E30200088A +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008DD3A0008E3020008E302000899 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008C93A0008E3020008E30200084D +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F032FE3E +:1003500003F040FE4FF055301F491B4A91423CBF0D +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F04AFE03F09EFE70 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F032BE000600200022002034 +:1003D0000000000808ED00E00000002000060020FA +:1003E000484B0008002200206422002068220020E0 +:1003F00044480020E0020008E0020008E002000893 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002002F0E6F8FEE702F017 +:1004300075F800DFFEE7000038B500F045FC00F07D +:1004400015FE02F015FD054602F048FD0446C0B950 +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F00CFD0CB100F030 +:1004700075F800F099FD284600F01EF900F06EF8BE +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0E5FBA0F120035842584108BD23 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000F5FB03B05DF804FB38B5302383F31188F6 +:1004C000174803680BB102F063F90023154A4FF493 +:1004D0007A71134802F052F9002383F31188124C09 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0B4FC322363602B78032B07D16368BF +:100510002BB9022000F0AAFC4FF47A73636038BD57 +:1005200068220020B90400088823002080220020CF +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F085BC022000F072BC024B0022A9 +:100550005A6070478022002088230020F8B5504B55 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0C0FB0220FFF7CBFF454B0021D3F852 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F017FCB14A83 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB102F053F80023AB4A4FF4B2 +:1006F0007A71A94802F042F8002383F31188009B25 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F093FB24B19C4B1B6838 +:10073000002B00F02682002000F092FA0390039B29 +:10074000002BF2DB012000F073FB039B213B1F2BEE +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F04FFA91E785 +:100800004FF47A7000F02CFA071EEBDB0220FFF7A2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F034FA17E004215548F9E704215A483A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F061FA0421059005A800F01EFAD2 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F08CFB26B10BF009 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F030FA0220FFF73BFE1FFA86F84046B0 +:1008C00000F038FA0446B0B1039940460136A1F170 +:1008D00040025142514100F03DFA0028EDD1BA46A4 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0D4F916E725460120FFF719FE244B36 +:100900009B68AB4207D9284600F006FA013040F058 +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940008FF9B0F10008FFF64DAF18F003077FF400 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F074F90390039A002AFFF69E +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200208423002068220020B9040008DF +:1009A000882300208022002004220020082200202A +:1009B0000C22002084220020C820FFF769FD074692 +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F066FA019AFF217F4800F087FA4FEA8B +:1009F000A803C8F387027C492846019300F086FAD1 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0B8F9F6 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F061FB8046E7E7384600F05CF9B8 +:100A60000590F2E7CDF81480042105A800F016F9EE +:100A700002E70023642104A8049300F005F900288C +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F073F90590E6E70023642104A8A8 +:100AA000049300F0F1F800287FF49CAE0220FFF7D9 +:100AB000EFFC00283FF496AE049800F061F9EAE7F5 +:100AC0000220FFF7E5FC00283FF48CAE00F070F93F +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F06BF907460421049004A800F0DC +:100AF000D5F83946B9E7322000F0B2F8071EFFF604 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0F0F80421059005A800F07F +:100B4000ADF8F1E74FF47A70FFF7A2FC00283FF40C +:100B500049AE00F01DF9002844D00A9B01330BD0A8 +:100B600008220AA9002000F0D1F900283AD020225A +:100B7000FF210AA800F0C2F9FFF792FC1C4801F01F +:100B800041FD13B0BDE8F08F002E3FF42BAE0BF00B +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F072F8074600287FF41CAE0220FFF721 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F01FFD059800F02EFA46463C469D +:100BD00000F0E0F9A6E506464EE64FF0000901E612 +:100BE000BA467EE637467CE68422002000220020BA +:100BF000A08601002DE9F84F4FF47A7306460D46A2 +:100C0000002402FB03F7DFF85080DFF8509098F9DA +:100C100000305FFA84FA5A1C01D0A34212D159F86D +:100C200024002A4631460368D3F820B03B46D84713 +:100C3000854207D1074B012083F800A0BDE8F88F5B +:100C40000124E4E7002CFBD04FF4FA7001F0DAFC49 +:100C50000020F3E7D42300201022002014220020DB +:100C6000002307B5024601210DF107008DF807307A +:100C7000FFF7C0FF20B19DF8070003B05DF804FB4B +:100C80004FF0FF30F9E700000A46042108B5FFF7EE +:100C9000B1FF80F00100C0B2404208BD074B0A46D8 +:100CA00030B41978064B53F821400146236820469A +:100CB000DD69044BAC4630BC604700BFD423002044 +:100CC00014220020A086010070B5104C0025104EA3 +:100CD00001F0B6FF20803068238883420CD80025BD +:100CE0002088013801F0A8FF23880544013BB5F5B1 +:100CF000802F2380F4D370BD01F09EFF336805443C +:100D00000133B5F5003F3360E5D3E8E7D623002093 +:100D10009023002002F062B800F1006000F500307E +:100D20000068704700F10060920000F5003001F0AB +:100D3000E3BF0000054B1A68054B1B889B1A8342D2 +:100D400002D9104401F078BF0020704790230020A2 +:100D5000D623002038B50446074D29B12868204421 +:100D6000BDE8384001F080BF2868204401F06AFFE8 +:100D70000028F3D038BD00BF90230020002070472A +:100D800000F1FF5000F58F10D0F800087047000008 +:100D9000064991F8243033B100230822086A81F80B +:100DA0002430FFF7BFBF0120704700BF942300200D +:100DB000014B1868704700BF0010005C194B0138E8 +:100DC0000322084470B51D68174BC5F30B042D0CA6 +:100DD0001E88A6420BD15C680A46013C824213463B +:100DE0000FD214F9016F4EB102F8016BF6E7013A28 +:100DF00003F10803ECD181420B4602D22C2203F806 +:100E0000012B0424094A1688AE4204D1984284BFBB +:100E1000967803F8016B013C02F10402F3D1581AF1 +:100E200070BD00BF0010005C1C2200202847000895 +:100E3000022804D1054B4FF480129A6170470128B3 +:100E4000FCD1024B4FF48002F7E700BF00100258BC +:100E5000022803D1044B10229A6170470128FCD16B +:100E6000014B4022F8E700BF00100258022805D1CC +:100E7000064A536983F01003536170470128FCD17F +:100E8000024A536983F04003F6E700BF001002589E +:100E900070B504464FF47A764CB1412C254628BFF4 +:100EA000412506FB05F0641B01F0ACFBF4E770BDC7 +:100EB000002310B5934203D0CC5CC4540133F9E74E +:100EC00010BD0000013810B510F9013F3BB191F998 +:100ED00000409C4203D11AB10131013AF4E71AB142 +:100EE00091F90020981A10BD1046FCE7034602460F +:100EF000D01A12F9011B0029FAD1704702440346A7 +:100F0000934202D003F8011BFAE770472DE9F8433A +:100F10001F4D14460746884695F8242052BBDFF83B +:100F200070909CB395F824302BB92022FF214846BD +:100F30002F62FFF7E3FF95F824004146C0F1080255 +:100F400005EB8000A24228BF2246D6B29200FFF7EE +:100F5000AFFF95F82430A41B17441E449044E4B21C +:100F6000F6B2082E85F82460DBD1FFF711FF0028C8 +:100F7000D7D108E02B6A03EB82038342CFD0FFF77F +:100F800007FF0028CBD10020BDE8F8830120FBE754 +:100F900094230020024B1A78024B1A70704700BF4E +:100FA000D42300201022002038B51A4C1A4D2046B8 +:100FB00000F07CFE2946204600F0A4FE2D684FF488 +:100FC0007A70D5F89020D2F8043843F00203C2F8C2 +:100FD0000438FFF75DFF1149284600F0A1FFD5F85E +:100FE00090200F4DD2F80438286823F002030D49F1 +:100FF000A042C2F804384FF4E1330B6001D000F096 +:10100000B3FD6868A04204D00649BDE8384000F04E +:10101000ABBD38BD382B0020244900082C490008FE +:1010200014220020BC2300200C4B70B50C4D04464C +:101030001E780C4B55F826209A420DD00A4B002101 +:1010400018221846FFF75AFF0460014655F826009B +:10105000BDE8704000F088BD70BD00BFD423002003 +:1010600014220020382B0020BC230020F0B5A1B0B2 +:1010700071B600230120002480261A46194600F08C +:101080004BFA4FF4D067214A3D25136923BBD2F8B0 +:1010900010310BBB036804F1006199600368C3F869 +:1010A0000CD003685E6003681F6001680B6843F042 +:1010B00001030B6001680B6823F01E030B600168DD +:1010C0000B68DB07FCD4037B8034416805FA03F32B +:1010D000B4F5001F0B60D8D100F05EFAB4F5001F24 +:1010E00011D000240A4E0B4D012001F077FE338809 +:1010F000A34205D928682044013401F0B5FDF6E784 +:10110000002001F06BFE61B621B0F0BD002000525E +:10111000D62300209023002030B50A44084D914288 +:101120000DD011F8013B5840082340F30004013B67 +:101130002C4013F0FF0384EA5000F6D1EFE730BDF6 +:101140002083B8ED08B5074B074A196801F03D0147 +:10115000996053680BB190689847BDE8084001F06A +:10116000FFBE00BF00000240D823002008B5084B96 +:101170001968890901F03D018A019A60054AD3681E +:101180000BB110699847BDE8084001F0E9BE00BF07 +:1011900000000240D823002008B5084B1968090C4C +:1011A00001F03D010A049A60054A53690BB1906948 +:1011B0009847BDE8084001F0D3BE00BF00000240E0 +:1011C000D823002008B5084B1968890D01F03D01AE +:1011D0008A059A60054AD3690BB1106A9847BDE841 +:1011E000084001F0BDBE00BF00000240D82300202F +:1011F00008B5074B074A596801F03D01D960536AA9 +:101200000BB1906A9847BDE8084001F0A9BE00BF45 +:1012100000000240D823002008B5084B596889090E +:1012200001F03D018A01DA60054AD36A0BB1106B07 +:101230009847BDE8084001F093BE00BF000002409F +:10124000D823002008B5084B5968090C01F03D016E +:101250000A04DA60054A536B0BB1906B9847BDE8FE +:10126000084001F07DBE00BF00000240D8230020EE +:1012700008B5084B5968890D01F03D018A05DA600F +:10128000054AD36B0BB1106C9847BDE8084001F0DC +:1012900067BE00BF00000240D823002008B5074BFE +:1012A000074A196801F03D019960536C0BB1906CCD +:1012B0009847BDE8084001F053BE00BF000402405B +:1012C000D823002008B5084B1968890901F03D01B1 +:1012D0008A019A60054AD36C0BB1106D9847BDE83E +:1012E000084001F03DBE00BF00040240D8230020AA +:1012F00008B5084B1968090C01F03D010A049A6011 +:10130000054A536D0BB1906D9847BDE8084001F058 +:1013100027BE00BF00040240D823002008B5084BB8 +:101320001968890D01F03D018A059A60054AD36D5F +:101330000BB1106E9847BDE8084001F011BE00BF28 +:1013400000040240D823002008B5074B074A59681B +:1013500001F03D01D960536E0BB1906E9847BDE826 +:10136000084001F0FDBD00BF00040240D82300206A +:1013700008B5084B5968890901F03D018A01DA6016 +:10138000054AD36E0BB1106F9847BDE8084001F0D5 +:10139000E7BD00BF00040240D823002008B5084B79 +:1013A0005968090C01F03D010A04DA60054A536FDF +:1013B0000BB1906F9847BDE8084001F0D1BD00BF68 +:1013C00000040240D823002008B5084B5968890D55 +:1013D00001F03D018A05DA60054AD36F13B1D2F8F6 +:1013E00080009847BDE8084001F0BABD0004024003 +:1013F000D823002000230C4910B51A460B4C0B6073 +:1014000054F82300026001EB430004334260402B98 +:10141000F6D1074A4FF0FF339360D360C2F8083427 +:10142000C2F80C3410BD00BFD82300203847000894 +:10143000000002400F28F8B510D9102810D011284C +:1014400011D0122808D10F240720DFF8C8E00126A8 +:10145000DEF80050A04208D9002653E00446F4E725 +:101460000F240020F1E70724FBE706FA00F73D42CE +:101470004AD1264C4FEA001C3D4304EB00160EEB0C +:10148000C000CEF80050C0E90123FBB273B1204880 +:10149000D0F8D83043F00103C0F8D830D0F800318C +:1014A00043F00103C0F80031D0F8003117F47F4F4A +:1014B0000ED01748D0F8D83043F00203C0F8D83027 +:1014C000D0F8003143F00203C0F80031D0F8003109 +:1014D00054F80C00036823F01F030360056815F03F +:1014E0000105FBD104EB0C033D2493F80CC05F68AD +:1014F00004FA0CF43C6021240560446112B1987B2D +:1015000000F066F93046F8BD0130A3E7384700081F +:1015100000440258D823002010B5302484F31188E9 +:10152000FFF788FF002383F3118810BD10B5044630 +:10153000807B00F063F901231549627B03FA02F214 +:101540000B6823EA0203DAB20B6072B9114AD2F8CF +:10155000D81021F00101C2F8D810D2F8001121F002 +:101560000101C2F80011D2F8002113F47F4F0ED10F +:10157000084BD3F8D82022F00202C3F8D820D3F8C1 +:10158000002122F00202C3F80021D3F8003110BD7F +:10159000D82300200044025808B5302383F3118873 +:1015A000FFF7C4FF002383F3118808BD0268436876 +:1015B0001143016003B1184770470000024A1368E5 +:1015C00043F0C003136070470010014013B50E4C88 +:1015D000204600F0BDFA04F1140000234FF400721D +:1015E0000A49009400F07AF9094B4FF40072094956 +:1015F00004F13800009400F0F3F9074A074BC4E9FE +:10160000172302B010BD00BF5C240020C8240020B6 +:10161000BD150008C82600200010014000E1F505B6 +:10162000037C30B5244C002918BF0C46012B11D186 +:10163000224B98420ED1224BD3F8F02042F01002F8 +:10164000C3F8F020D3F8182142F01002C3F8182193 +:10165000D3F818312268036EC16D03EB5203846620 +:10166000B3FBF2F36268150442BF23F0070503F0F1 +:10167000070343EA4503CB60A36843F040034B6094 +:10168000E36843F001038B6042F4967343F0010377 +:101690000B604FF0FF330B62510505D512F010229D +:1016A00005D0B2F1805F04D080F8643030BD7F2374 +:1016B000FAE73F23F8E700BF384800085C24002021 +:1016C000004402582DE9F047C66D05463768F469B5 +:1016D000210734621AD014F0080118BF4FF480714A +:1016E000E20748BF41F02001A3074FF0300348BF95 +:1016F00041F04001600748BF41F0800183F3118849 +:10170000281DFFF753FF002383F31188E2050AD554 +:10171000302383F311884FF48061281DFFF746FFC3 +:10172000002383F311884FF030094FF0000A14F0C2 +:10173000200838D13B0616D54FF0300905F1380A9C +:10174000200610D589F31188504600F07DF9002855 +:1017500036DA0821281DFFF729FF27F080033360C0 +:10176000002383F31188790614D5620612D530233D +:1017700083F31188D5E913239A4208D12B6C33B136 +:1017800027F040071021281DFFF710FF37600023C6 +:1017900083F31188E30618D5AA6E1369ABB15069BB +:1017A000BDE8F047184789F31188736A284695F811 +:1017B0006410194000F0E6F98AF31188F469B6E77D +:1017C000B06288F31188F469BAE7BDE8F0870000D9 +:1017D000090100F16043012203F56143C9B283F8B6 +:1017E000001300F01F039A4043099B0003F160437C +:1017F00003F56143C3F880211A60704700F01F03AE +:1018000001229A40430900F160409B0000F56140CD +:1018100003F1604303F56143C3F88020C3F88021DE +:10182000002380F800337047F8B5154682680446F7 +:101830000B46AA4200D28568A1692669761AB5428C +:101840000BD218462A46FFF733FBA3692B44A3614A +:101850002846A3685B1BA360F8BD0CD9AF1B1846D4 +:101860003246FFF725FB3A46E1683044FFF720FB9C +:10187000E3683B44EBE718462A46FFF719FBE368A9 +:10188000E5E7000083689342F7B50446154600D2A9 +:101890008568D4E90460361AB5420BD22A46FFF7B0 +:1018A00007FB63692B4463612846A3685B1BA36045 +:1018B00003B0F0BD0DD93246AF1B0191FFF7F8FA26 +:1018C00001993A46E0683144FFF7F2FAE3683B4495 +:1018D000E9E72A46FFF7ECFAE368E4E710B50A44C3 +:1018E0000024C361029B8460C16002610362C0E99D +:1018F0000000C0E9051110BD08B5D0E905329342DA +:1019000001D1826882B98268013282605A1C4261C8 +:1019100019700021D0E904329A4224BFC3684361A0 +:1019200000F08CFE002008BD4FF0FF30FBE7000008 +:1019300070B5302304460E4683F31188A568A5B11F +:10194000A368A269013BA360531CA36115782269B7 +:10195000934224BFE368A361E3690BB12046984733 +:10196000002383F31188284607E03146204600F023 +:1019700055FE0028E2DA85F3118870BD2DE9F74F96 +:1019800004460E4617469846D0F81C904FF0300A91 +:101990008AF311884FF0000B154665B12A4631468F +:1019A0002046FFF741FF034660B94146204600F05C +:1019B00035FE0028F1D0002383F31188781B03B093 +:1019C000BDE8F08FB9F1000F03D001902046C84761 +:1019D000019B8BF31188ED1A1E448AF31188DCE712 +:1019E000C160C361009B82600362C0E905111144BC +:1019F000C0E9000001617047F8B504460D4616467F +:101A0000302383F31188A768A7B1A368013BA360C3 +:101A100063695A1C62611D70D4E904329A4224BF82 +:101A2000E3686361E3690BB120469847002080F3C7 +:101A3000118807E03146204600F0F0FD0028E2DA88 +:101A400087F31188F8BD0000D0E9052310B59A424C +:101A500001D182687AB982680021013282605A1C01 +:101A600082611C7803699A4224BFC368836100F0D5 +:101A7000E5FD204610BD4FF0FF30FBE72DE9F74FA5 +:101A800004460E4617469846D0F81C904FF0300A90 +:101A90008AF311884FF0000B154665B12A4631468E +:101AA0002046FFF7EFFE034660B94146204600F0AE +:101AB000B5FD0028F1D0002383F31188781B03B013 +:101AC000BDE8F08FB9F1000F03D001902046C84760 +:101AD000019B8BF31188ED1A1E448AF31188DCE711 +:101AE000026843681143016003B118477047000062 +:101AF0001430FFF743BF00004FF0FF331430FFF7FF +:101B00003DBF00003830FFF7B9BF00004FF0FF3392 +:101B10003830FFF7B3BF00001430FFF709BF0000F3 +:101B20004FF0FF311430FFF703BF00003830FFF7EC +:101B300063BF00004FF0FF323830FFF75DBF000099 +:101B4000012914BF6FF0130000207047FFF73EBD5E +:101B5000044B036000234360C0E902330123037494 +:101B6000704700BF5048000810B53023044683F387 +:101B70001188FFF755FD02230020237480F311889C +:101B800010BD000038B5C36904460D461BB90421D9 +:101B90000844FFF7A5FF294604F11400FFF7ACFE47 +:101BA000002806DA201D4FF40061BDE83840FFF739 +:101BB00097BF38BD026843681143016003B11847FD +:101BC0007047000013B5406B00F58054D4F8A4387A +:101BD0001A681178042914D1017C022911D11979CC +:101BE000012312898B4013420BD101A94C3002F022 +:101BF000A7F8D4F8A4480246019B2179206800F098 +:101C0000DFF902B010BD0000143002F029B8000066 +:101C10004FF0FF33143002F023B800004C3002F0D4 +:101C2000FBB800004FF0FF334C3002F0F5B8000075 +:101C3000143001F0F7BF00004FF0FF31143001F015 +:101C4000F1BF00004C3002F0C7B800004FF0FF3287 +:101C50004C3002F0C1B800000020704710B500F50C +:101C60008054D4F8A4381A681178042917D1017C5B +:101C7000022914D15979012352898B4013420ED184 +:101C8000143001F089FF024648B1D4F8A4484FF45B +:101C9000407361792068BDE8104000F07FB910BD45 +:101CA000406BFFF7DBBF0000704700007FB5124BB1 +:101CB00001250426044603600023057400F1840214 +:101CC00043602946C0E902330C4B02901430019363 +:101CD0004FF44073009601F03BFF094B04F6944229 +:101CE000294604F14C000294CDE900634FF440739F +:101CF00002F002F804B070BD78480008A11C00088A +:101D0000C51B00080A68302383F311880B790B3355 +:101D100042F823004B79133342F823008B7913B137 +:101D20000B3342F8230000F58053C3F8A4180223B4 +:101D30000374002080F311887047000038B5037FDA +:101D4000044613B190F85430ABB90125201D02218F +:101D5000FFF730FF04F114006FF00101257700F068 +:101D600079FC04F14C0084F854506FF00101BDE897 +:101D7000384000F06FBC38BD10B501210446043076 +:101D8000FFF718FF0023237784F8543010BD0000BC +:101D900038B504460025143001F0F2FE04F14C0081 +:101DA000257701F0C1FF201D84F854500121FFF771 +:101DB00001FF2046BDE83840FFF750BF90F8803063 +:101DC00003F06003202B06D190F881200023212A04 +:101DD00003D81F2A06D800207047222AFBD1C0E969 +:101DE0001D3303E0034A426707228267C36701206D +:101DF000704700BF3422002037B500F58055D5F874 +:101E0000A4381A68117804291AD1017C022917D143 +:101E10001979012312898B40134211D100F14C042E +:101E2000204602F041F858B101A9204601F088FF90 +:101E3000D5F8A4480246019B2179206800F0C0F83B +:101E400003B030BD01F10B03F0B550F8236085B04D +:101E500004460D46FEB1302383F3118804EB850759 +:101E6000301D0821FFF7A6FEFB6806F14C005B69F8 +:101E70001B681BB1019001F071FF019803A901F0EB +:101E80005FFF024648B1039B2946204600F098F8C0 +:101E9000002383F3118805B0F0BDFB685A6912680E +:101EA000002AF5D01B8A013B1340F1D104F18002D6 +:101EB000EAE70000133138B550F82140ECB1302387 +:101EC00083F3118804F58053D3F8A428136852795A +:101ED00003EB8203DB689B695D6845B104216018F0 +:101EE000FFF768FE294604F1140001F05FFE20466A +:101EF000FFF7B4FE002383F3118838BD704700005C +:101F000001F02CB901234022002110B5044600F84D +:101F1000303BFEF7F3FF0023C4E9013310BD00009E +:101F200010B53023044683F3118824224160002138 +:101F30000C30FEF7E3FF204601F032F902230020C7 +:101F4000237080F3118810BD70B500EB8103054646 +:101F500050690E461446DA6018B110220021FEF7CF +:101F6000CDFFA06918B110220021FEF7C7FF31464E +:101F70002846BDE8704001F019BA000083682022AD +:101F8000002103F0011310B5044683601030FEF702 +:101F9000B5FF2046BDE8104001F094BAF0B4012529 +:101FA00000EB810447898D40E4683D43A469458185 +:101FB00023600023A2606360F0BC01F0B1BA0000AE +:101FC000F0B4012500EB810407898D40E4683D43AE +:101FD0006469058123600023A2606360F0BC01F0A6 +:101FE00027BB000070B5022300250446242203709D +:101FF0002946C0F888500C3040F8045CFEF77EFF9C +:10200000204684F8705001F065F963681B6823B1BD +:1020100029462046BDE87040184770BD0378052B5F +:1020200010B504460AD080F88C300523037043684D +:102030001B680BB1042198470023A36010BD00006A +:102040000178052906D190F88C20436802701B683E +:1020500003B118477047000070B590F8703004461F +:1020600013B1002380F8703004F18002204601F0A3 +:102070004DFA63689B68B3B994F8803013F060053B +:1020800035D00021204601F03FFD0021204601F01F +:102090002FFD63681B6813B106212046984706236D +:1020A00084F8703070BD204698470028E4D0B4F81A +:1020B0008630A26F9A4288BFA36794F98030A56FDB +:1020C000002B4FF0300380F20381002D00F0F280EE +:1020D000092284F8702083F3118800212046D4E976 +:1020E0001D23FFF76DFF002383F31188DAE794F8CF +:1020F000812003F07F0343EA022340F2023293423D +:1021000000F0C58021D8B3F5807F48D00DD8012BD1 +:102110003FD0022B00F09380002BB2D104F1880253 +:1021200062670222A267E367C1E7B3F5817F00F02F +:102130009B80B3F5407FA4D194F88230012BA0D1CD +:10214000B4F8883043F0020332E0B3F5006F4DD0AD +:1021500017D8B3F5A06F31D0A3F5C063012B90D889 +:102160006368204694F882205E6894F88310B4F87F +:102170008430B047002884D0436863670368A3674E +:102180001AE0B3F5106F36D040F6024293427FF466 +:1021900078AF5C4B63670223A3670023C3E794F81F +:1021A0008230012B7FF46DAFB4F8883023F0020346 +:1021B000A4F88830C4E91D55E56778E7B4F88030A5 +:1021C000B3F5A06F0ED194F88230204684F88A309F +:1021D00001F0DEF863681B6813B1012120469847BF +:1021E000032323700023C4E91D339CE704F18B0310 +:1021F00063670123C3E72378042B10D1302383F3D3 +:1022000011882046FFF7BAFE85F311880321636821 +:1022100084F88B5021701B680BB12046984794F8C6 +:102220008230002BDED084F88B3004232370636867 +:102230001B68002BD6D0022120469847D2E794F89D +:10224000843020461D0603F00F010AD501F050F935 +:10225000012804D002287FF414AF2B4B9AE72B4BB4 +:1022600098E701F037F9F3E794F88230002B7FF418 +:1022700008AF94F8843013F00F01B3D01A0620464B +:1022800002D501F059FCADE701F04AFCAAE794F849 +:102290008230002B7FF4F5AE94F8843013F00F01F8 +:1022A000A0D01B06204602D501F02EFC9AE701F0D3 +:1022B0001FFC97E7142284F8702083F311882B46C3 +:1022C0002A4629462046FFF769FE85F31188E9E68C +:1022D0005DB1152284F8702083F311880021204617 +:1022E000D4E91D23FFF75AFEFDE60B2284F8702087 +:1022F00083F311882B462A4629462046FFF760FEC5 +:10230000E3E700BFA8480008A0480008A448000868 +:1023100038B590F870300446002B3ED0063BDAB258 +:102320000F2A34D80F2B32D8DFE803F037313108C9 +:10233000223231313131313131313737856FB0F8B7 +:1023400086309D4214D2C3681B8AB5FBF3F203FBAF +:1023500012556DB9302383F311882B462A4629463E +:10236000FFF72EFE85F311880A2384F870300EE003 +:10237000142384F87030302383F31188002320461F +:102380001A461946FFF70AFE002383F3118838BD69 +:10239000C36F03B198470023E7E70021204601F00F +:1023A000B3FB0021204601F0A3FB63681B6813B157 +:1023B0000621204698470623D7E7000010B590F87D +:1023C00070300446142B29D017D8062B05D001D81D +:1023D0001BB110BD093B022BFBD80021204601F0A8 +:1023E00093FB0021204601F083FB63681B6813B157 +:1023F000062120469847062319E0152BE9D10B2327 +:1024000080F87030302383F3118800231A46194670 +:10241000FFF7D6FD002383F31188DAE7C3689B69D1 +:102420005B68002BD5D1C36F03B19847002384F8B4 +:102430007030CEE700238268037503691B689968D2 +:102440009142FBD25A680360426010605860704746 +:1024500000238268037503691B6899689142FBD861 +:102460005A680360426010605860704708B50846BB +:10247000302383F311880B7D032B05D0042B0DD063 +:102480002BB983F3118808BD8B6900221A604FF0C5 +:10249000FF338361FFF7CEFF0023F2E7D1E900327B +:1024A00013605A60F3E70000FFF7C4BF054BD9681B +:1024B00008751868026853601A600122D8600275B6 +:1024C000FDF7A0BFC82800200C4B30B5DD684B1CC1 +:1024D00087B004460FD02B46094A684600F04EF9F3 +:1024E0002046FFF7E3FF009B13B1684600F050F968 +:1024F000A86907B030BDFFF7D9FFF9E7C828002069 +:102500006D240008044B1A68DB6890689B68984249 +:1025100094BF002001207047C8280020084B10B548 +:102520001C68D868226853601A600122DC6022753A +:10253000FFF78EFF01462046BDE81040FDF762BF61 +:10254000C828002038B5074C012300250649074854 +:102550002370656001F0E6FC0223237085F3118887 +:1025600038BD00BF302B0020B0480008C82800202C +:1025700000F044B9034A516853685B1A9842FBD88B +:10258000704700BF001000E08B600223086108461E +:102590008B8270478368A3F1840243F8142C02698C +:1025A00043F8442C426943F8402C094A43F8242C50 +:1025B000C268A3F1200043F8182C022203F80C2C67 +:1025C000002203F80B2C034A43F8102C704700BF7D +:1025D0001D040008C828002008B5FFF7DBFFBDE890 +:1025E0000840FFF761BF0000024BDB6898610F20D5 +:1025F000FFF75CBFC8280020302383F31188FFF762 +:10260000F3BF000008B50146302383F3118808208A +:10261000FFF75AFF002383F3118808BD064BDB68E0 +:1026200039B1426818605A60136043600420FFF7B4 +:102630004BBF4FF0FF307047C82800200368984216 +:1026400006D01A680260506018469961FFF72CBFE7 +:102650007047000038B504460D462068844200D11A +:1026600038BD036823605C608561FFF71DFFF4E7F8 +:10267000036810B59C68A2420CD85C688A600B6045 +:102680004C602160596099688A1A9A604FF0FF3354 +:10269000836010BD121B1B68ECE700000A2938BFDD +:1026A0000A2170B504460D460A26601901F032FC75 +:1026B00001F01AFC041BA54203D8751C04462E46E3 +:1026C000F3E70A2E04D90120BDE8704001F06ABC8E +:1026D00070BD0000F8B5144B0D460A2A4FF00A07EA +:1026E000D96103F11001826038BF0A224160196983 +:1026F0001446016048601861A81801F0FBFB01F066 +:10270000F3FB431B0646A34206D37C1C281927462D +:10271000354601F0FFFBF2E70A2F04D90120BDE89E +:10272000F84001F03FBCF8BDC8280020F8B50646C7 +:102730000D4601F0D9FB0F4A134653F8107F9F4214 +:1027400006D12A4601463046BDE8F840FFF7C2BF31 +:10275000D169BB68441A2C1928BF2C46A34202D960 +:102760002946FFF79BFF224631460348BDE8F84063 +:10277000FFF77EBFC8280020D8280020C0E9032327 +:10278000002310B45DF8044B4361FFF7CFBF000096 +:1027900010B5194C236998420DD08168D0E90032F8 +:1027A00013605A609A680A449A60002303604FF0ED +:1027B000FF33A36110BD0268234643F8102F536016 +:1027C0000022026022699A4203D1BDE8104001F064 +:1027D0009BBB936881680B44936001F085FB226981 +:1027E000E1699268441AA242E4D91144BDE810405C +:1027F000091AFFF753BF00BFC82800202DE9F04792 +:10280000DFF8BC8008F110072C4ED8F8105001F00A +:102810006BFBD8F81C40AA68031B9A423ED81444AC +:102820004FF00009D5E90032C8F81C4013605A6027 +:10283000C5F80090D8F81030B34201D101F064FB24 +:1028400089F31188D5E9033128469847302383F36B +:1028500011886B69002BD8D001F046FB6A69A0EBA8 +:10286000040982464A450DD2022001F09BFB00225A +:10287000D8F81030B34208D151462846BDE8F04799 +:10288000FFF728BF121A2244F2E712EB0909294682 +:10289000384638BF4A46FFF7EBFEB5E7D8F81030A8 +:1028A000B34208D01444C8F81C00211AA960BDE83E +:1028B000F047FFF7F3BEBDE8F08700BFD82800203F +:1028C000C828002000207047FEE700007047000085 +:1028D0004FF0FF307047000002290CD0032904D0CC +:1028E0000129074818BF00207047032A05D805486A +:1028F00000EBC2007047044870470020704700BFDB +:1029000088490008442200203C49000870B59AB06C +:1029100005460846144601A900F0C2F801A8FEF7D2 +:10292000E5FA431C0022C6B25B001046C5E900343C +:1029300023700323023404F8013C01ABD1B202340A +:102940008E4201D81AB070BD13F8011B013204F891 +:10295000010C04F8021CF1E708B5302383F3118859 +:102960000348FFF749FA002383F3118808BD00BF2D +:10297000382B002090F8803003F01F02012A07D185 +:1029800090F881200B2A03D10023C0E91D3315E004 +:1029900003F06003202B08D1B0F884302BB990F8F5 +:1029A0008120212A03D81F2A04D8FFF707BA222A38 +:1029B000EBD0FAE7034A426707228267C367012028 +:1029C000704700BF3B22002007B5052917D8DFE874 +:1029D00001F0191603191920302383F31188104AC6 +:1029E00001210190FFF7B0FA019802210D4AFFF78B +:1029F000ABFA0D48FFF7CCF9002383F3118803B03D +:102A00005DF804FB302383F311880748FFF796F93C +:102A1000F2E7302383F311880348FFF7ADF9EBE7C2 +:102A2000DC48000800490008382B002038B50C4D60 +:102A30000C4C2A460C4904F10800FFF767FF05F12A +:102A4000CA0204F110000949FFF760FF05F5CA72D8 +:102A500004F118000649BDE83840FFF757BF00BF32 +:102A60001044002044220020BC480008C64800084A +:102A7000D148000870B5044608460D46FEF736FA00 +:102A8000C6B22046013403780BB9184670BD3246F1 +:102A90002946FEF717FA0028F3D10120F6E70000D7 +:102AA0002DE9F84F05460C46FEF720FA2C49C6B230 +:102AB0002846FFF7DFFF08B10336F6B2294928465A +:102AC000FFF7D8FF08B11036F6B2632E0DD8DFF845 +:102AD0009080DFF89090244FDFF894A0DFF894B056 +:102AE0002E7846B92670BDE8F88F29462046BDE805 +:102AF000F84F01F0FBBD252E2ED107224146284676 +:102B0000FEF7E0F970B9DBF8003007350A3444F815 +:102B10000A3CDBF8043044F8063CBBF8083024F8E3 +:102B2000023CDDE7082249462846FEF7CBF998B972 +:102B3000A21C0E4B197802320909C95D02F8041C67 +:102B400013F8011B01F00F015345C95D02F8031C86 +:102B5000F0D118340835C3E7013504F8016BBFE73D +:102B6000A8490008D1480008BB49000800E8F11F47 +:102B70000CE8F11FB0490008BFF34F8F044B1A69EE +:102B80005107FCD1D3F810215207F8D1704700BF8C +:102B90000020005208B50D4B1B78ABB9FFF7ECFFD6 +:102BA0000B4BDA68D10704D50A4A5A6002F1883221 +:102BB0005A60D3F80C21D20706D5064AC3F804217F +:102BC00002F18832C3F8042108BD00BF6E46002020 +:102BD000002000522301674508B5114B1B78F3B95B +:102BE000104B1A69510703D5DA6842F04002DA60E7 +:102BF000D3F81021520705D5D3F80C2142F040023A +:102C0000C3F80C21FFF7B8FF064BDA6842F0010267 +:102C1000DA60D3F80C2142F00102C3F80C2108BDA0 +:102C20006E460020002000520F289ABF00F58060F9 +:102C300040040020704700004FF40030704700004F +:102C4000102070470F2808B50BD8FFF7EDFF00F5EF +:102C500000330268013204D104308342F9D10120EB +:102C600008BD0020FCE700000F2838B505463FD816 +:102C7000FFF782FF1F4CFFF78DFF4FF0FF33072850 +:102C80006361C4F814311DD82361FFF775FF030297 +:102C900043F02403E360E36843F08003E3602369C7 +:102CA0005A07FCD42846FFF767FFFFF7BDFF4FF434 +:102CB000003100F0F5F82846FFF78EFFBDE83840F8 +:102CC000FFF7C0BFC4F81031FFF756FFA0F10803AB +:102CD0001B0243F02403C4F80C31D4F80C3143F048 +:102CE0008003C4F80C31D4F810315B07FBD4D9E76A +:102CF000002038BD002000522DE9F84F05460C4653 +:102D0000104645EA0203DE0602D00020BDE8F88F37 +:102D100020F01F00DFF8BCB0DFF8BCA0FFF73AFFDF +:102D200004EB0008444503D10120FFF755FFEDE710 +:102D300020222946204601F0C9FC10B92035203454 +:102D4000F0E72B4605F120021F68791CDDD1043322 +:102D50009A42F9D105F178431B481C4EB3F5801F08 +:102D60001B4B38BF184603F1F80332BFD946D14692 +:102D70001E46FFF701FF0760A5EB040C336804F162 +:102D80001C0143F002033360231FD9F8007017F0D1 +:102D90000507FAD153F8042F8B424CF80320F4D1E5 +:102DA000BFF34F8FFFF7E8FE4FF0FF33202221469D +:102DB00003602846336823F00203336001F086FC89 +:102DC0000028BBD03846B0E7142100520C20005236 +:102DD00014200052102000521021005210B5084C4F +:102DE000237828B11BB9FFF7D5FE0123237010BD4E +:102DF000002BFCD02070BDE81040FFF7EDBE00BFF7 +:102E00006E4600200244074BD2B210B5904200D16A +:102E100010BD441C00B253F8200041F8040BE0B28E +:102E2000F4E700BF504000580E4B30B51C6F24042F +:102E300005D41C6F1C671C6F44F400441C670A4CCB +:102E400002442368D2B243F480732360074B90425C +:102E500000D130BD441C51F8045B00B243F820504F +:102E6000E0B2F4E7004402580048025850400058CD +:102E700007B5012201A90020FFF7C4FF019803B0A4 +:102E80005DF804FB13B50446FFF7F2FFA04205D03E +:102E9000012201A900200194FFF7C6FF02B010BD76 +:102EA0000144BFF34F8F064B884204D3BFF34F8FCB +:102EB000BFF36F8F7047C3F85C022030F4E700BFA8 +:102EC00000ED00E0034B1A681AB9034AD2F8D02487 +:102ED0001A607047704600200040025808B5FFF79E +:102EE000F1FF024B1868C0F3806008BD70460020F7 +:102EF000EFF30983054968334A6B22F001024A6304 +:102F000083F30988002383F31188704700EF00E002 +:102F1000302080F3118862B60D4B0E4AD96821F437 +:102F2000E0610904090C0A430B49DA60D3F8FC207C +:102F300042F08072C3F8FC20084AC2F8B01F116842 +:102F400041F0010111602022DA7783F822007047F6 +:102F500000ED00E00003FA0555CEACC5001000E01E +:102F6000302310B583F311880E4B5B6813F40063B4 +:102F700014D0F1EE103AEFF309844FF08073683CFF +:102F8000E361094BDB6B236684F30988FFF7BAFA28 +:102F900010B1064BA36110BD054BFBE783F311880D +:102FA000F9E700BF00ED00E000EF00E02F040008AB +:102FB0003204000870B5BFF34F8FBFF36F8F1A4A0A +:102FC0000021C2F85012BFF34F8FBFF36F8F5369C8 +:102FD00043F400335361BFF34F8FBFF36F8FC2F8D9 +:102FE0008410BFF34F8FD2F8803043F6E074C3F300 +:102FF000C900C3F34E335B0103EA0406014646EA07 +:1030000081750139C2F86052F9D2203B13F1200FCB +:10301000F2D1BFF34F8F536943F480335361BFF351 +:103020004F8FBFF36F8F70BD00ED00E0FEE7000033 +:10303000214B2248224A70B5904237D3214BC11E02 +:10304000DA1C121A22F003028B4238BF0022002140 +:10305000FDF754FF1C4A0023C2F88430BFF34F8FA2 +:10306000D2F8803043F6E074C3F3C900C3F34E33A3 +:103070005B0103EA0406014646EA81750139C2F89C +:103080006C52F9D2203B13F1200FF2D1BFF34F8FD6 +:10309000BFF36F8FBFF34F8FBFF36F8F0023C2F863 +:1030A0005032BFF34F8FBFF36F8F70BD53F8041BC7 +:1030B00040F8041BC0E700BFAC4B000844480020A8 +:1030C000444800204448002000ED00E0074BD3F8BE +:1030D000D81021EA0001C3F8D810D3F8002122EA61 +:1030E0000002C3F80021D3F80031704700440258B1 +:1030F00070B5D0E9244300224FF0FF359E6804EB01 +:1031000042135101D3F80009002805DAD3F8000969 +:1031100040F08040C3F80009D3F8000B002805DA1E +:10312000D3F8000B40F08040C3F8000B0132631865 +:103130009642C3F80859C3F8085BE0D24FF0011378 +:10314000C4F81C3870BD0000890141F02001016104 +:1031500003699B06FCD41220FFF70CBA10B50A4C89 +:103160002046FEF7CFFE094BC4F89030084BC4F858 +:103170009430084C2046FEF7C5FE074BC4F890304B +:10318000064BC4F8943010BD74460020000008407F +:10319000F04900081047002000000440FC490008E6 +:1031A00070B503780546012B5CD1434BD0F89040B5 +:1031B000984258D1414B0E216520D3F8D82042F0D7 +:1031C0000062C3F8D820D3F8002142F00062C3F8AF +:1031D0000021D3F80021D3F8802042F00062C3F828 +:1031E0008020D3F8802022F00062C3F88020D3F83A +:1031F0008030FEF7EDFA324BE360324BC4F8003812 +:103200000023D5F89060C4F8003EC02323604FF43B +:103210000413A3633369002BFCDA01230C20336110 +:10322000FFF7A8F93369DB07FCD41220FFF7A2F9F6 +:103230003369002BFCDA00262846A660FFF758FF0A +:103240006B68C4F81068DB68C4F81468C4F81C68BC +:1032500083BB1D4BA3614FF0FF336361A36843F051 +:103260000103A36070BD194B9842C9D1134B4FF0B5 +:103270008060D3F8D82042F00072C3F8D820D3F889 +:10328000002142F00072C3F80021D3F80021D3F8E6 +:10329000802042F00072C3F88020D3F8802022F012 +:1032A0000072C3F88020D3F88030FFF70FFF0E21A3 +:1032B0004D209EE7064BCDE774460020004402589F +:1032C0004014004003002002003C30C010470020A2 +:1032D000083C30C0F8B5D0F89040054600214FF0CA +:1032E00000662046FFF730FFD5F8941000234FF01A +:1032F00001128F684FF0FF30C4F83438C4F81C282E +:1033000004EB431201339F42C2F80069C2F8006B1C +:10331000C2F80809C2F8080BF2D20B68D5F8902061 +:10332000C5F89830636210231361166916F0100611 +:10333000FBD11220FFF71EF9D4F8003823F4FE6306 +:10334000C4F80038A36943F4402343F01003A36199 +:103350000923C4F81038C4F814380B4BEB604FF055 +:10336000C043C4F8103B094BC4F8003BC4F81069D3 +:10337000C4F80039D5F8983003F1100243F48013F3 +:10338000C5F89820A362F8BDCC4900084080001021 +:10339000D0F8902090F88A10D2F8003823F4FE6319 +:1033A00043EA0113C2F80038704700002DE9F843E2 +:1033B00000EB8103D0F890500C468046DA680FFA93 +:1033C00081F94801166806F00306731E022B05EB0F +:1033D00041134FF0000194BFB604384EC3F8101BE0 +:1033E0004FF0010104F1100398BF06F1805601FA75 +:1033F00003F3916998BF06F5004600293AD0578A31 +:1034000004F15801374349016F50D5F81C180B439C +:103410000021C5F81C382B180127C3F81019A74044 +:103420005369611E9BB3138A928B9B08012A88BF44 +:103430005343D8F89820981842EA034301F1400218 +:103440002146C8F89800284605EB82025360FFF732 +:103450007BFE08EB8900C3681B8A43EA8453483427 +:103460001E4364012E51D5F81C381F43C5F81C7843 +:10347000BDE8F88305EB4917D7F8001B21F400419C +:10348000C7F8001BD5F81C1821EA0303C0E704F1B4 +:103490003F030B4A2846214605EB83035A60FFF79A +:1034A00053FE05EB4910D0F8003923F40043C0F86F +:1034B0000039D5F81C3823EA0707D7E70080001049 +:1034C00000040002D0F894201268C0F89820FFF79A +:1034D0000FBE00005831D0F8903049015B5813F40A +:1034E000004004D013F4001F0CBF022001207047DD +:1034F0004831D0F8903049015B5813F4004004D0B3 +:1035000013F4001F0CBF02200120704700EB810163 +:10351000CB68196A0B6813604B68536070470000F2 +:1035200000EB810330B5DD68AA691368D36019B96F +:10353000402B84BF402313606B8A1468D0F890201E +:103540001C4402EB4110013C09B2B4FBF3F46343A9 +:10355000033323F0030343EAC44343F0C043C0F8FA +:10356000103B2B6803F00303012B0ED1D2F808386F +:1035700002EB411013F4807FD0F8003B14BF43F0FE +:10358000805343F00053C0F8003B02EB4112D2F8E5 +:10359000003B43F00443C2F8003B30BD2DE9F0414D +:1035A000D0F8906005460C4606EB4113D3F8087B33 +:1035B0003A07C3F8087B08D5D6F814381B0704D59A +:1035C00000EB8103DB685B689847FA071FD5D6F8E4 +:1035D0001438DB071BD505EB8403D968CCB98B699C +:1035E000488A5A68B2FBF0F600FB16228AB91868BE +:1035F000DA6890420DD2121AC3E90024302383F313 +:10360000118821462846FFF78BFF84F31188BDE817 +:10361000F081012303FA04F26B8923EA02036B8130 +:10362000CB68002BF3D021462846BDE8F04118476F +:1036300000EB81034A0170B5DD68D0F890306C6909 +:103640002668E66056BB1A444FF40020C2F8100901 +:103650002A6802F00302012A0AB20ED1D3F8080840 +:1036600003EB421410F4807FD4F8000914BF40F03B +:10367000805040F00050C4F8000903EB4212D2F829 +:10368000000940F00440C2F800090122D3F83408D0 +:1036900002FA01F10143C3F8341870BD19B9402E84 +:1036A00084BF4020206020681A442E8A8419013C7F +:1036B000B4FBF6F440EAC44040F00050C6E7000016 +:1036C0002DE9F843D0F8906005460C464F0106EB13 +:1036D0004113D3F8088918F0010FC3F808891CD0EA +:1036E000D6F81038DB0718D500EB8103D3F80CC0EF +:1036F000DCF81430D3F800E0DA68964530D2A2EB5B +:103700000E024FF000091A60C3F80490302383F3CF +:103710001188FFF78DFF89F3118818F0800F1DD0F5 +:10372000D6F834380126A640334217D005EB84037F +:103730000134D5F89050D3F80CC0E4B22F44DCF833 +:10374000142005EB0434D2F800E05168714514D31D +:10375000D5F8343823EA0606C5F83468BDE8F8839E +:10376000012303FA01F2038923EA02030381DCF84F +:103770000830002BD1D09847CFE7AEEB0103BCF85F +:103780001000834228BF0346D7F8180980B2B3EB74 +:10379000800FE3D89068A0F1040959F8048FC4F8A9 +:1037A0000080A0EB09089844B8F1040FF5D818443C +:1037B0000B4490605360C8E72DE9F84FD0F8905063 +:1037C00004466E69AB691E4016F480586E6103D0E2 +:1037D000BDE8F84FFEF706BC002E12DAD5F8003E21 +:1037E0009B0705D0D5F8003E23F00303C5F8003E43 +:1037F000D5F80438204623F00103C5F80438FEF755 +:103800001FFC370505D52046FFF772FC2046FEF762 +:1038100005FCB0040CD5D5F8083813F0060FEB689A +:1038200023F470530CBF43F4105343F4A053EB60E4 +:1038300031071BD56368DB681BB9AB6923F008034C +:10384000AB612378052B0CD1D5F8003E9A0705D043 +:10385000D5F8003E23F00303C5F8003E2046FEF7EE +:10386000EFFB6368DB680BB120469847F30200F179 +:10387000BA80B70226D5D4F8909000274FF0010AFD +:1038800009EB4712D2F8003B03F44023B3F5802F35 +:1038900011D1D2F8003B002B0DDA62890AFA07F346 +:1038A00022EA0303638104EB8703DB68DB6813B15F +:1038B0003946204698470137D4F89430FFB29B68C8 +:1038C0009F42DDD9F00619D5D4F89000026AC2F300 +:1038D0000A1702F00F0302F4F012B2F5802F00F085 +:1038E000CA80B2F5402F09D104EB8303002200F512 +:1038F0008050DB681B6A974240F0B0803003D5F8F7 +:10390000185835D5E90303D500212046FFF746FEB8 +:10391000AA0303D501212046FFF740FE6B0303D520 +:1039200002212046FFF73AFE2F0303D5032120464C +:10393000FFF734FEE80203D504212046FFF72EFEF0 +:10394000A90203D505212046FFF728FE6A0203D508 +:1039500006212046FFF722FE2B0203D50721204631 +:10396000FFF71CFEEF0103D508212046FFF716FEE6 +:10397000700340F1A780E90703D500212046FFF737 +:103980009FFEAA0703D501212046FFF799FE6B078A +:1039900003D502212046FFF793FE2F0703D503210D +:1039A0002046FFF78DFEEE0603D504212046FFF7E3 +:1039B00087FEA80603D505212046FFF781FE69068C +:1039C00003D506212046FFF77BFE2A0603D50721F3 +:1039D0002046FFF775FEEB0574D520460821BDE8AB +:1039E000F84FFFF76DBED4F890904FF0000B4FF0FA +:1039F000010AD4F894305FFA8BF79B689F423FF638 +:103A000038AF09EB4713D3F8002902F44022B2F58E +:103A1000802F20D1D3F80029002A1CDAD3F80029FE +:103A200042F09042C3F80029D3F80029002AFBDBBA +:103A30003946D4F89000FFF787FB22890AFA07F38A +:103A400022EA0303238104EB8703DB689B6813B13D +:103A50003946204698470BF1010BCAE7910701D17F +:103A6000D0F80080072A02F101029CBF03F8018B05 +:103A70004FEA18283FE704EB830300F58050DA682B +:103A8000D2F818C0DCF80820DCE9001CA1EB0C0C13 +:103A900000218F4208D1DB689B699A683A449A609A +:103AA0005A683A445A6029E711F0030F01D1D0F85F +:103AB00000808C4501F1010184BF02F8018B4FEABF +:103AC0001828E6E7BDE8F88F08B50348FFF774FE4D +:103AD000BDE80840FFF744BA7446002008B5034823 +:103AE000FFF76AFEBDE80840FFF73ABA104700202A +:103AF000D0F8903003EB4111D1F8003B43F40013B0 +:103B0000C1F8003B70470000D0F8903003EB411142 +:103B1000D1F8003943F40013C1F8003970470000B0 +:103B2000D0F8903003EB4111D1F8003B23F400139F +:103B3000C1F8003B70470000D0F8903003EB411112 +:103B4000D1F8003923F40013C1F8003970470000A0 +:103B500030B50433039C0172002104FB0325C160CE +:103B6000C0E90653049B0363059BC0E90000C0E95C +:103B70000422C0E90842C0E90A11436330BD0000D5 +:103B80000022416AC260C0E90411C0E90A226FF054 +:103B90000101FEF75FBD0000D0E90432934201D17C +:103BA000C2680AB9181D7047002070470369196080 +:103BB0000021C2680132C260C26913448269934223 +:103BC000036124BF436A0361FEF738BD38B504467C +:103BD0000D46E3683BB162690020131D1268A362C1 +:103BE0001344E36207E0237A33B929462046FEF7FF +:103BF00015FD0028EDDA38BD6FF00100FBE700008D +:103C0000C368C269013BC36043691344826993423C +:103C1000436124BF436A436100238362036B03B1A2 +:103C20001847704770B53023044683F31188866ABD +:103C30003EB9FFF7CBFF054618B186F31188284639 +:103C400070BDA36AE26A13F8015B9342A36202D3D8 +:103C50002046FFF7D5FF002383F31188EFE700002C +:103C60002DE9F84F04460E46174698464FF03009A6 +:103C700089F311880025AA46D4F828B0BBF1000FBB +:103C800009D141462046FFF7A1FF20B18BF31188EF +:103C90002846BDE8F88FD4E90A12A7EB050B521AA3 +:103CA000934528BF9346BBF1400F1BD9334601F122 +:103CB000400251F8040B914243F8040BF9D1A36A76 +:103CC000403640354033A362D4E90A239A4202D3F6 +:103CD0002046FFF795FF8AF31188BD42D8D289F3B9 +:103CE0001188C9E730465A46FDF7E2F8A36A5E44F8 +:103CF0005D445B44A362E7E710B5029C04330172A4 +:103D000003FB0421C460C0E906130023C0E90A33A1 +:103D1000039B0363049BC0E90000C0E90422C0E9DF +:103D20000842436310BD0000026A6FF00101C260E7 +:103D3000426AC0E904220022C0E90A22FEF78ABCD6 +:103D4000D0E904239A4201D1C26822B9184650F83A +:103D5000043B0B60704700231846FAE7C368002154 +:103D6000C2690133C360436913448269934243616A +:103D700024BF436A4361FEF761BC000038B50446C6 +:103D80000D46E3683BB1236900201A1DA262E26977 +:103D90001344E36207E0237A33B929462046FEF74D +:103DA0003DFC0028EDDA38BD6FF00100FBE70000B4 +:103DB00003691960C268013AC260C269134482692A +:103DC0009342036124BF436A036100238362036B50 +:103DD00003B118477047000070B530230D46044604 +:103DE000114683F31188866A2EB9FFF7C7FF10B119 +:103DF00086F3118870BDA36A1D70A36AE26A01335D +:103E00009342A36204D3E16920460439FFF7D0FF4F +:103E1000002080F31188EDE72DE9F84F04460D46A8 +:103E2000904699464FF0300A8AF311880026B3462F +:103E3000A76A4FB949462046FFF7A0FF20B187F394 +:103E400011883046BDE8F88FD4E90A073A1AA8EB82 +:103E50000607974228BF1746402F1BD905F140039C +:103E600055F8042B9D4240F8042BF9D1A36A403643 +:103E70004033A362D4E90A239A4204D3E16920467D +:103E80000439FFF795FF8BF311884645D9D28AF3A1 +:103E90001188CDE729463A46FDF70AF8A36A3D4462 +:103EA0003E443B44A362E5E7D0E904239A4217D19C +:103EB000C3689BB1836A8BB1043B9B1A0ED013601D +:103EC000C368013BC360C3691A4483699A420261B3 +:103ED00024BF436A036100238362012318467047AD +:103EE0000023FBE700F024B9014B586A704700BF7C +:103EF000000C0040034B002258631A610222DA6072 +:103F0000704700BF000C0040014B0022DA60704790 +:103F1000000C0040014B5863704700BF000C00408C +:103F2000FEE7000070B51B4B0025044686B05860C4 +:103F30000E4685620163FEF7EBFF04F11003A560F6 +:103F4000E562C4E904334FF0FF33C4E90044C4E937 +:103F50000635FFF7C9FF2B46024604F1340120461F +:103F6000C4E9082380230C4A2565FEF70DFB0123D5 +:103F70000A4AE06000920375684672680192B2686E +:103F8000CDE90223064BCDE90435FEF725FB06B04B +:103F900070BD00BF302B0020084A00080D4A000801 +:103FA000213F0008024AD36A1843D062704700BF1D +:103FB000C82800204B6843608B688360CB68C3606F +:103FC0000B6943614B6903628B6943620B68036051 +:103FD0007047000008B53C4B40F2FF713B48D3F8F6 +:103FE00088200A43C3F88820D3F8882022F4FF628F +:103FF00022F00702C3F88820D3F88820D3F8E02005 +:104000000A43C3F8E020D3F808210A43C3F8082183 +:104010002F4AD3F808311146FFF7CCFF00F5806036 +:1040200002F11C01FFF7C6FF00F5806002F13801C4 +:10403000FFF7C0FF00F5806002F15401FFF7BAFFFF +:1040400000F5806002F17001FFF7B4FF00F58060B9 +:1040500002F18C01FFF7AEFF00F5806002F1A801CC +:10406000FFF7A8FF00F5806002F1C401FFF7A2FF8F +:1040700000F5806002F1E001FFF79CFF00F5806031 +:1040800002F1FC01FFF796FF02F58C7100F58060EC +:10409000FFF790FF00F018F90E4BD3F8902242F092 +:1040A0000102C3F89022D3F8942242F00102C3F82F +:1040B00094220522C3F898204FF06052C3F89C2048 +:1040C000054AC3F8A02008BD004402580000025869 +:1040D000144A000800ED00E01F00080308B500F0D6 +:1040E000D5FAFEF72FFA0F4BD3F8DC2042F040024E +:1040F000C3F8DC20D3F8042122F04002C3F80421E5 +:10410000D3F80431084B1A6842F008021A601A68A2 +:1041100042F004021A60FEF7D5FEBDE80840FEF743 +:1041200085BC00BF004402580018024870470000D8 +:10413000114BD3F8E82042F00802C3F8E820D3F886 +:10414000102142F00802C3F810210C4AD3F81031B4 +:10415000D36B43F00803D363C722094B9A624FF035 +:10416000FF32DA6200229A615A63DA605A600122F1 +:104170005A611A60704700BF004402580010005C8A +:10418000000C0040094A08B51169D3680B40D9B248 +:104190009B076FEA0101116107D5302383F3118872 +:1041A000FEF7E6F9002383F3118808BD000C0040F8 +:1041B000064BD3F8DC200243C3F8DC20D3F80421FB +:1041C0001043C3F80401D3F8043170470044025887 +:1041D00008B53C4B4FF0FF31D3F8802062F000422D +:1041E000C3F88020D3F8802002F00042C3F880207A +:1041F000D3F88020D3F88420C3F88410D3F8842027 +:104200000022C3F88420D3F88400D86F40F0FF4028 +:1042100040F4FF0040F4DF4040F07F00D867D86FE3 +:1042200020F0FF4020F4FF0020F4DF4020F07F006A +:10423000D867D86FD3F888006FEA40506FEA5050C3 +:10424000C3F88800D3F88800C0F30A00C3F88800D8 +:10425000D3F88800D3F89000C3F89010D3F89000FA +:10426000C3F89020D3F89000D3F89400C3F89410CA +:10427000D3F89400C3F89420D3F89400D3F89800AE +:10428000C3F89810D3F89800C3F89820D3F8980092 +:10429000D3F88C00C3F88C10D3F88C00C3F88C20B2 +:1042A000D3F88C00D3F89C00C3F89C10D3F89C1072 +:1042B000C3F89C20D3F89C30FDF79CF8BDE808407B +:1042C00000F0B8B90044025808B50122534BC3F8B6 +:1042D0000821534BD3F8F42042F00202C3F8F42033 +:1042E000D3F81C2142F00202C3F81C210222D3F8A9 +:1042F0001C314C4BDA605A689104FCD54A4A1A606A +:1043000001229A60494ADA6000221A614FF4404261 +:104310009A61444B9A699204FCD51A6842F48072FF +:104320001A603F4B1A6F12F4407F04D04FF4803272 +:104330001A6700221A671A6842F001021A60384BA5 +:104340001A685007FCD500221A611A6912F0380267 +:10435000FBD1012119604FF0804159605A67344AFE +:10436000DA62344A1A611A6842F480321A602C4BBD +:104370001A689103FCD51A6842F480521A601A68D0 +:104380009204FCD52C4A2D499A6200225A63196383 +:1043900001F57C01DA6301F2E71199635A64284A56 +:1043A0001A64284ADA621A6842F0A8521A601C4B52 +:1043B0001A6802F02852B2F1285FF9D148229A61B6 +:1043C0004FF48862DA6140221A621F4ADA641F4A97 +:1043D0001A651F4A5A651F4A9A6532231E4A13609E +:1043E000136803F00F03022BFAD10D4A136943F04F +:1043F00003031361136903F03803182BFAD14FF04C +:104400000050FFF7D5FE4FF08040FFF7D1FE4FF090 +:104410000040BDE80840FFF7CBBE00BF0080005160 +:10442000004402580048025800C000F00200000199 +:104430000000FF01008890081210200063020901AB +:10444000470E0508DD0BBF01200000200000011011 +:104450000910E00000010110002000524FF0B042AE +:1044600008B5D2F8883003F00103C2F8883023B1D0 +:10447000044A13680BB150689847BDE80840FEF73E +:104480006FBD00BFC44700204FF0B04208B5D2F85E +:10449000883003F00203C2F8883023B1044A9368DD +:1044A0000BB1D0689847BDE80840FEF759BD00BF82 +:1044B000C44700204FF0B04208B5D2F8883003F06E +:1044C0000403C2F8883023B1044A13690BB1506960 +:1044D0009847BDE80840FEF743BD00BFC447002031 +:1044E0004FF0B04208B5D2F8883003F00803C2F8A4 +:1044F000883023B1044A93690BB1D0699847BDE86D +:104500000840FEF72DBD00BFC44700204FF0B04269 +:1045100008B5D2F8883003F01003C2F8883023B110 +:10452000044A136A0BB1506A9847BDE80840FEF789 +:1045300017BD00BFC44700204FF0B04310B5D3F8FB +:10454000884004F47872C3F88820A30604D5124A80 +:10455000936A0BB1D06A9847600604D50E4A136B74 +:104560000BB1506B9847210604D50B4A936B0BB1E6 +:10457000D06B9847E20504D5074A136C0BB1506C19 +:104580009847A30504D5044A936C0BB1D06C9847A7 +:10459000BDE81040FEF7E4BCC44700204FF0B04334 +:1045A00010B5D3F8884004F47C42C3F88820620533 +:1045B00004D5164A136D0BB1506D9847230504D5E9 +:1045C000124A936D0BB1D06D9847E00404D50F4AA1 +:1045D000136E0BB1506E9847A10404D50B4A936E2D +:1045E0000BB1D06E9847620404D5084A136F0BB123 +:1045F000506F9847230404D5044A936F0BB1D06FD2 +:104600009847BDE81040FEF7ABBC00BFC447002090 +:1046100008B50348FDF756F8BDE80840FEF7A0BC12 +:104620005C24002008B5FFF7ADFDBDE80840FEF7AB +:1046300097BC0000062108B50846FDF7C9F8062119 +:104640000720FDF7C5F806210820FDF7C1F806216F +:104650000920FDF7BDF806210A20FDF7B9F806216B +:104660001720FDF7B5F806212820FDF7B1F809213C +:104670007A20FDF7ADF807213220FDF7A9F80C21CB +:104680002520BDE80840FDF7A3B8000008B5FFF7F6 +:104690009FFD00F00DF8FDF759FAFDF731FCFDF72D +:1046A00003FBFFF743FDBDE80840FFF71BBC00001C +:1046B0000023054A19460133102BC2E9001102F10B +:1046C0000802F8D1704700BFC447002010B5013977 +:1046D0000244904201D1002005E0037811F8014F17 +:1046E000A34201D0181B10BD0130F2E7034611F8B8 +:1046F000012B03F8012B002AF9D1704753544D3395 +:104700003248373F3F3F0053544D333248373378B8 +:104710002F3732780053544D3332483734332F37E4 +:1047200035332F373530000001105A00031059007F +:1047300001205800032056001000024008000240EB +:104740000008024000000B00280002400800024060 +:104750000408024006010C0040000240080002402C +:104760000808024010020D005800024008000240F4 +:104770000C08024016030E00700002400C000240BC +:104780001008024000040F00880002400C000240A4 +:104790001408024006051000A00002400C00024070 +:1047A0001808024010061100B80002400C00024038 +:1047B0001C08024016072F001004024008040240A3 +:1047C0002008024000083800280402400804024083 +:1047D000240802400609390040040240080402404F +:1047E00028080240100A3A00580402400804024017 +:1047F0002C080240160B3B00700402400C040240DF +:1048000030080240000C3C00880402400C040240C6 +:1048100034080240060D4400A00402400C0402408B +:1048200038080240100E4500B80402400C04024053 +:104830003C080240160F46000096000000000000F1 +:104840000000000000000000000000000000000068 +:10485000000000000D1B0008F91A0008351B0008B5 +:10486000211B00082D1B0008191B0008051B000850 +:10487000F11A0008411B000800000000251C000878 +:10488000111C00084D1C0008391C0008451C0008BC +:10489000311C00081D1C0008091C0008591C0008D8 +:1048A0000000000001000000000000006330000074 +:1048B000AC48000820290020302B0020417264758C +:1048C00050696C6F740025424F415244252D424C73 +:1048D000002553455249414C2500000002000000CC +:1048E00000000000451E0008B51E00084000400002 +:1048F000E0430020F0430020020000000000000020 +:104900000300000000000000FD1E00080000000081 +:104910001000000000440020000000000100000022 +:10492000000000007446002001010200C9290008AF +:10493000D9280008752900085929000843000000FB +:104940004449000809024300020100C03209040082 +:1049500000010202010005240010010524010001EC +:10496000042402020524060001070582030800FF53 +:1049700009040100020A00000007050102400000CE +:104980000705810240000000120000009049000865 +:1049900012011001020000400912415700020102F9 +:1049A000030100000403090425424F41524425003D +:1049B0004D69636F416972373433003031323334BB +:1049C000353637383941424344454600000000003F +:1049D0005920000811230008BD23000840004000B2 +:1049E000AC470020AC47002001000000BC4700207D +:1049F00080000000400100000800000000010000ED +:104A000000100000080000006D61696E0069646CB0 +:104A1000650000000000A86A00000000AAAAAAAA77 +:104A200000001464FFFF00000000000070A70A00EF +:104A30000000000100000000AAAAAAAA00000001CC +:104A4000FFFF000000000000000000000000000068 +:104A500000000000AAAAAAAA00000000FFFF0000B0 +:104A60000000000000000000000500000000000041 +:104A7000AAAAAAAA00050000FFFF0000000000008B +:104A8000000000000011000000000000AAAAAAAA6D +:104A900000000000AFFF0000000000000000000068 +:104AA0000000000000000000AAAAAAAA000000005E +:104AB000FFFF0000000000000000000000000000F8 +:104AC00000000000AAAAAAAA00000000FFFF000040 +:104AD00000000000000000000000000000000000D6 +:104AE000AAAAAAAA00000000FFFF00000000000020 +:104AF000000000000000000000000000AAAAAAAA0E +:104B000000000000FFFF00000000000000000000A7 +:104B10000000000000000000AAAAAAAA00000000ED +:104B2000FFFF000000000000000000000000000087 +:104B300000000000AAAAAAAA00000000FFFF0000CF +:104B400000000000000000008E04000000000000D3 +:104B500000001A0000000000FF000000382B0020B9 +:104B60005C24002000000000FC46000883040000D4 +:104B70000747000850040000154700080096000091 +:104B8000000008009600000000080000040000007B +:104B9000A449000800000000000000000000000020 +:0C4BA00000000000000000000000000009 +:00000001FF diff --git a/Tools/bootloaders/NxtPX4v2_bl.bin b/Tools/bootloaders/NxtPX4v2_bl.bin new file mode 100644 index 0000000000000..07c2d5d2d93a1 Binary files /dev/null and b/Tools/bootloaders/NxtPX4v2_bl.bin differ diff --git a/Tools/bootloaders/NxtPX4v2_bl.hex b/Tools/bootloaders/NxtPX4v2_bl.hex new file mode 100644 index 0000000000000..b9dbf29471ba9 --- /dev/null +++ b/Tools/bootloaders/NxtPX4v2_bl.hex @@ -0,0 +1,1107 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008B128000828 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E30200081D3E0008493E0008D4 +:10006000753E0008A13E0008CD3E0008BD10000806 +:10007000E5100008111100083D1100086911000881 +:1000800091110008BD110008E3020008E302000816 +:10009000E3020008E3020008E3020008F93E00085A +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E0005D3F0008E3020008E3020008E3020008A5 +:1000F000E3020008E3020008E3020008E911000837 +:10010000E3020008E3020008D13F0008E302000810 +:10011000E3020008E3020008E3020008E30200082B +:10012000151200083D120008691200089512000817 +:10013000C1120008E3020008E3020008E30200081D +:10014000E3020008E3020008E3020008E3020008FB +:10015000E91200081513000841130008E302000823 +:10016000E3020008E3020008E3020008E3020008DB +:10017000E30200089D340008E3020008E3020008DF +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000889340008E3020008E302000893 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F012FB61 +:1003500003F020FB4FF055301F491B4A91423CBF30 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F02AFB03F07EFBB6 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F012BB000600200022002057 +:1003D0000000000808ED00E00000002000060020FA +:1003E000A8440008002200205C2200206022002097 +:1003F000BC430020E0020008E0020008E002000820 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0CAFDFEE701F030 +:1004300059FD00DFFEE7000038B500F02FFC00F0AA +:10044000D1FD02F0F5F9054602F028FA0446C0B9DC +:100450000E4B9D4217D001339D4241F2883512BFA9 +:10046000044600250124002002F0ECF90CB100F054 +:1004700075F800F08BFD284600F01EF900F06EF8CC +:10048000F9E70025EFE70546EDE700BF010007B0FB +:1004900008B500F0D5FBA0F120035842584108BD33 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000E5FB03B05DF804FB38B5302383F3118806 +:1004C000174803680BB101F047FE0023154A4FF4AB +:1004D0007A71134801F036FE002383F31188124C21 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0A4FC322363602B78032B07D16368CF +:100510002BB9022000F09AFC4FF47A73636038BD67 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F071BC022000F05CBC024B0022D3 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0AAFB0220FFF7CBFF454B0021D3F868 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F009FCB14A91 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F037FD0023AB4A4FF4CA +:1006F0007A71A94801F026FD002383F31188009B3D +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F07FFB24B19C4B1B684C +:10073000002B00F02682002000F082FA0390039B39 +:10074000002BF2DB012000F05DFB039B213B1F2B04 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F03FFA91E795 +:100800004FF47A7000F01CFA071EEBDB0220FFF7B2 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F024FA17E004215548F9E704215A484A +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F04BFA0421059005A800F00EFAF8 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F07EFB26B10BF017 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F01AFA0220FFF73BFE1FFA86F84046C6 +:1008C00000F022FA0446B0B1039940460136A1F186 +:1008D00040025142514100F027FA0028EDD1BA46BA +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0C4F916E725460120FFF719FE244B46 +:100900009B68AB4207D9284600F0F0F9013040F06F +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:100940007FF9B0F10008FFF64DAF18F003077FF410 +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F064F90390039A002AFFF6AE +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F058FA019AFF217F4800F079FA4FEAA7 +:1009F000A803C8F387027C492846019300F078FADF +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0A2F90C +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F01DFB8046E7E7384600F046F912 +:100A60000590F2E7CDF81480042105A800F006F9FE +:100A700002E70023642104A8049300F0F5F800289D +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F05DF90590E6E70023642104A8BE +:100AA000049300F0E1F800287FF49CAE0220FFF7E9 +:100AB000EFFC00283FF496AE049800F04BF9EAE70B +:100AC0000220FFF7E5FC00283FF48CAE00F05AF955 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F055F907460421049004A800F0F2 +:100AF000C5F83946B9E7322000F0A2F8071EFFF624 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0DAF80421059005A800F095 +:100B40009DF8F1E74FF47A70FFF7A2FC00283FF41C +:100B500049AE00F007F9002844D00A9B01330BD0BE +:100B600008220AA9002000F0C3F900283AD0202268 +:100B7000FF210AA800F0B4F9FFF792FC1C4801F02D +:100B800025FA13B0BDE8F08F002E3FF42BAE0BF02A +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F062F8074600287FF41CAE0220FFF731 +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F003FA059800F00AFA46463C46E0 +:100BD00000F0D2F9A6E506464EE64FF0000901E620 +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A08601000F4B70B51B780C460133DBB2A9 +:100C0000012B11D80C4D4FF47A732968A2FB0332E3 +:100C100022460E6A01462846B047844204D1074B5B +:100C2000002201201A7070BD4FF4FA7001F0CEF965 +:100C30000020F8E710220020B0260020B423002076 +:100C4000002307B5024601210DF107008DF807309A +:100C5000FFF7D0FF20B19DF8070003B05DF804FB5B +:100C60004FF0FF30F9E700000A46042108B5FFF70E +:100C7000C1FF80F00100C0B2404208BD30B4054C55 +:100C80000A46014623682046DD69034BAC4630BC6A +:100C9000604700BFB0260020A086010070B5104C50 +:100CA0000025104E01F0ACFC208030682388834280 +:100CB0000CD800252088013801F09EFC23880544CB +:100CC000013BB5F5802F2380F4D370BD01F094FC77 +:100CD000336805440133B5F5003F3360E5D3E8E7F9 +:100CE000B62300208823002001F058BD00F10060E9 +:100CF00000F500300068704700F10060920000F5D8 +:100D0000003001F0D9BC0000054B1A68054B1B8868 +:100D10009B1A834202D9104401F06EBC0020704738 +:100D200088230020B623002038B50446074D29B19A +:100D300028682044BDE8384001F076BC286820448B +:100D400001F060FC0028F3D038BD00BF88230020EC +:100D50000020704700F1FF5000F58F10D0F8000818 +:100D600070470000064991F8243033B1002308226F +:100D7000086A81F82430FFF7BFBF0120704700BF29 +:100D80008C230020014B1868704700BF0010005CE6 +:100D9000194B01380322084470B51D68174BC5F381 +:100DA0000B042D0C1E88A6420BD15C680A46013C40 +:100DB000824213460FD214F9016F4EB102F8016B53 +:100DC000F6E7013A03F10803ECD181420B4602D267 +:100DD0002C2203F8012B0424094A1688AE4204D1C0 +:100DE000984284BF967803F8016B013C02F104023B +:100DF000F3D1581A70BD00BF0010005C142200200F +:100E0000C8400008022804D1054B4FF400429A6103 +:100E100070470128FCD1034B4FF40062F7E700BF95 +:100E200000040258000C0258022804D1054B4FF070 +:100E300000429A6170470128FCD1034B4FF00062D9 +:100E4000F7E700BF00040258000C0258022805D141 +:100E5000064A536983F40043536170470128FCD16B +:100E6000034A536983F40063F6E700BF00040258A5 +:100E7000000C025870B504464FF47A764CB1412C00 +:100E8000254628BF412506FB05F0641B01F09EF8AE +:100E9000F4E770BD002310B5934203D0CC5CC4547A +:100EA0000133F9E710BD0000013810B510F9013F1A +:100EB0003BB191F900409C4203D11AB10131013A92 +:100EC000F4E71AB191F90020981A10BD1046FCE71A +:100ED00003460246D01A12F9011B0029FAD17047C5 +:100EE00002440346934202D003F8011BFAE770471D +:100EF0002DE9F8431F4D14460746884695F82420EF +:100F000052BBDFF870909CB395F824302BB92022A7 +:100F1000FF2148462F62FFF7E3FF95F82400414682 +:100F2000C0F1080205EB8000A24228BF2246D6B2DB +:100F30009200FFF7AFFF95F82430A41B17441E441E +:100F40009044E4B2F6B2082E85F82460DBD1FFF7B6 +:100F500009FF0028D7D108E02B6A03EB8203834204 +:100F6000CFD0FFF7FFFE0028CBD10020BDE8F883EB +:100F70000120FBE78C230020024B1A78024B1A70E9 +:100F8000704700BFB42300201022002010B5114C80 +:100F9000114800F06FFB21460F4800F097FB2468D2 +:100FA0004FF47A70D4F89020D2F8043843F002035A +:100FB000C2F80438FFF75EFF0849204600F094FCB1 +:100FC000D4F89020D2F8043823F00203C2F8043891 +:100FD00010BD00BF84420008B02600208C420008EB +:100FE00070470000F0B5A1B071B6002301200024C5 +:100FF00080261A46194600F04BFA4FF4D067214A72 +:101000003D25136923BBD2F810310BBB036804F1F3 +:10101000006199600368C3F80CD003685E600368E0 +:101020001F6001680B6843F001030B6001680B68E7 +:1010300023F01E030B6001680B68DB07FCD4037B05 +:101040008034416805FA03F3B4F5001F0B60D8D172 +:1010500000F05EFAB4F5001F11D000240A4E0B4DCB +:10106000012001F09BFB3388A34205D92868204466 +:10107000013401F0D9FAF6E7002001F08FFB61B6E8 +:1010800021B0F0BD00200052B623002088230020AC +:1010900030B50A44084D91420DD011F8013B58403B +:1010A000082340F30004013B2C4013F0FF0384EAC3 +:1010B0005000F6D1EFE730BD2083B8ED08B5074BFF +:1010C000074A196801F03D01996053680BB19068B7 +:1010D0009847BDE8084001F023BC00BF0000024073 +:1010E000B823002008B5084B1968890901F03D01B3 +:1010F0008A019A60054AD3680BB110699847BDE828 +:10110000084001F00DBC00BF00000240B8230020E1 +:1011100008B5084B1968090C01F03D010A049A60F2 +:10112000054A53690BB190699847BDE8084001F042 +:10113000F7BB00BF00000240B823002008B5084BF1 +:101140001968890D01F03D018A059A60054AD36945 +:101150000BB1106A9847BDE8084001F0E1BB00BF41 +:1011600000000240B823002008B5074B074A596821 +:1011700001F03D01D960536A0BB1906A9847BDE810 +:10118000084001F0CDBB00BF00000240B8230020A2 +:1011900008B5084B5968890901F03D018A01DA60F8 +:1011A000054AD36A0BB1106B9847BDE8084001F0BF +:1011B000B7BB00BF00000240B823002008B5084BB1 +:1011C0005968090C01F03D010A04DA60054A536BC5 +:1011D0000BB1906B9847BDE8084001F0A1BB00BF80 +:1011E00000000240B823002008B5084B5968890D5B +:1011F00001F03D018A05DA60054AD36B0BB1106C32 +:101200009847BDE8084001F08BBB00BF00000240DA +:10121000B823002008B5074B074A196801F03D01C3 +:101220009960536C0BB1906C9847BDE8084001F091 +:1012300077BB00BF00040240B823002008B5084B6C +:101240001968890901F03D018A019A60054AD36C49 +:101250000BB1106D9847BDE8084001F061BB00BFBD +:1012600000040240B823002008B5084B1968090C97 +:1012700001F03D010A049A60054A536D0BB1906D6F +:101280009847BDE8084001F04BBB00BF0004024096 +:10129000B823002008B5084B1968890D01F03D01FD +:1012A0008A059A60054AD36D0BB1106E9847BDE868 +:1012B000084001F035BB00BF00040240B823002005 +:1012C00008B5074B074A596801F03D01D960536ED4 +:1012D0000BB1906E9847BDE8084001F021BB00BFFC +:1012E00000040240B823002008B5084B596889095A +:1012F00001F03D018A01DA60054AD36E0BB1106F2F +:101300009847BDE8084001F00BBB00BF0004024055 +:10131000B823002008B5084B5968090C01F03D01BD +:101320000A04DA60054A536F0BB1906F9847BDE825 +:10133000084001F0F5BA00BF00040240B8230020C5 +:1013400008B5084B5968890D01F03D018A05DA603E +:10135000054AD36F13B1D2F880009847BDE8084022 +:1013600001F0DEBA00040240B823002000230C493B +:1013700010B51A460B4C0B6054F82300026001EBC9 +:10138000430004334260402BF6D1074A4FF0FF334D +:101390009360D360C2F80834C2F80C3410BD00BFAB +:1013A000B8230020D8400008000002400F28F8B5FC +:1013B00010D9102810D0112811D0122808D10F24CC +:1013C0000720DFF8C8E00126DEF80050A04208D967 +:1013D000002653E00446F4E70F240020F1E7072439 +:1013E000FBE706FA00F73D424AD1264C4FEA001CC3 +:1013F0003D4304EB00160EEBC000CEF80050C0E9F0 +:101400000123FBB273B12048D0F8D83043F0010378 +:10141000C0F8D830D0F8003143F00103C0F80031F3 +:10142000D0F8003117F47F4F0ED01748D0F8D830DD +:1014300043F00203C0F8D830D0F8003143F0020383 +:10144000C0F80031D0F8003154F80C00036823F0E4 +:101450001F030360056815F00105FBD104EB0C03C5 +:101460003D2493F80CC05F6804FA0CF43C6021241E +:101470000560446112B1987B00F054F83046F8BD25 +:101480000130A3E7D840000800440258B8230020E8 +:1014900010B5302484F31188FFF788FF002383F30D +:1014A000118810BD10B50446807B00F051F801236F +:1014B0001549627B03FA02F20B6823EA0203DAB2EF +:1014C0000B6072B9114AD2F8D81021F00101C2F8AC +:1014D000D810D2F8001121F00101C2F80011D2F8A1 +:1014E000002113F47F4F0ED1084BD3F8D82022F0FF +:1014F0000202C3F8D820D3F8002122F00202C3F878 +:101500000021D3F8003110BDB82300200044025858 +:1015100008B5302383F31188FFF7C4FF002383F35A +:10152000118808BD090100F16043012203F5614300 +:10153000C9B283F8001300F01F039A4043099B00CF +:1015400003F1604303F56143C3F880211A607047DB +:1015500000F01F0301229A40430900F160409B0004 +:1015600000F5614003F1604303F56143C3F8802057 +:10157000C3F88021002380F8003370470268436875 +:101580001143016003B118477047000013B5406B69 +:1015900000F58054D4F8A4381A681178042914D1BD +:1015A000017C022911D11979012312898B40134240 +:1015B0000BD101A94C3002F0A3F8D4F8A44802469C +:1015C000019B2179206800F0DFF902B010BD000016 +:1015D000143002F025B800004FF0FF33143002F051 +:1015E0001FB800004C3002F0F7B800004FF0FF3396 +:1015F0004C3002F0F1B80000143001F0F3BF0000ED +:101600004FF0FF31143001F0EDBF00004C3002F01C +:10161000C3B800004FF0FF324C3002F0BDB80000FC +:101620000020704710B500F58054D4F8A4381A682B +:101630001178042917D1017C022914D15979012389 +:1016400052898B4013420ED1143001F085FF0246BF +:1016500048B1D4F8A4484FF4407361792068BDE8DC +:10166000104000F07FB910BD406BFFF7DBBF0000FA +:10167000704700007FB5124B012504260446036025 +:101680000023057400F1840243602946C0E9023357 +:101690000C4B0290143001934FF44073009601F00C +:1016A00037FF094B04F69442294604F14C0002949A +:1016B000CDE900634FF4407301F0FEFF04B070BD4C +:1016C000D8410008691600088D1500080A68302303 +:1016D00083F311880B790B3342F823004B791333D2 +:1016E00042F823008B7913B10B3342F8230000F545 +:1016F0008053C3F8A41802230374002080F31188D8 +:101700007047000038B5037F044613B190F8543099 +:10171000ABB90125201D0221FFF730FF04F11400B1 +:101720006FF00101257700F079FC04F14C0084F89A +:1017300054506FF00101BDE8384000F06FBC38BD77 +:1017400010B5012104460430FFF718FF002323776A +:1017500084F8543010BD000038B50446002514301C +:1017600001F0EEFE04F14C00257701F0BDFF201DD5 +:1017700084F854500121FFF701FF2046BDE83840AE +:10178000FFF750BF90F8803003F06003202B06D1A4 +:1017900090F881200023212A03D81F2A06D8002090 +:1017A0007047222AFBD1C0E91D3303E0034A426798 +:1017B00007228267C3670120704700BF2C220020E8 +:1017C00037B500F58055D5F8A4381A681178042982 +:1017D0001AD1017C022917D11979012312898B4072 +:1017E000134211D100F14C04204602F03DF858B1EB +:1017F00001A9204601F084FFD5F8A4480246019BC8 +:101800002179206800F0C0F803B030BD01F10B036E +:10181000F0B550F8236085B004460D46FEB1302384 +:1018200083F3118804EB8507301D0821FFF7A6FE1E +:10183000FB6806F14C005B691B681BB1019001F06D +:101840006DFF019803A901F05BFF024648B1039BBD +:101850002946204600F098F8002383F3118805B04C +:10186000F0BDFB685A691268002AF5D01B8A013B5B +:101870001340F1D104F18002EAE70000133138B5DA +:1018800050F82140ECB1302383F3118804F58053E4 +:10189000D3F8A4281368527903EB8203DB689B69B1 +:1018A0005D6845B104216018FFF768FE294604F120 +:1018B000140001F05BFE2046FFF7B4FE002383F323 +:1018C000118838BD7047000001F028B9012340227B +:1018D000002110B5044600F8303BFFF701FB002360 +:1018E000C4E9013310BD000010B53023044683F372 +:1018F00011882422416000210C30FFF7F1FA2046C4 +:1019000001F02EF902230020237080F3118810BD0E +:1019100070B500EB8103054650690E461446DA6047 +:1019200018B110220021FFF7DBFAA06918B11022CC +:101930000021FFF7D5FA31462846BDE8704001F096 +:1019400015BA000083682022002103F0011310B5AE +:10195000044683601030FFF7C3FA2046BDE810400C +:1019600001F090BAF0B4012500EB810447898D4065 +:10197000E4683D43A469458123600023A26063605D +:10198000F0BC01F0ADBA0000F0B4012500EB810419 +:1019900007898D40E4683D43646905812360002325 +:1019A000A2606360F0BC01F023BB000070B50223AD +:1019B00000250446242203702946C0F888500C30C4 +:1019C00040F8045CFFF78CFA204684F8705001F070 +:1019D00061F963681B6823B129462046BDE8704061 +:1019E000184770BD0378052B10B504460AD080F85F +:1019F0008C300523037043681B680BB104219847A2 +:101A00000023A36010BD00000178052906D190F8DD +:101A10008C20436802701B6803B1184770470000B0 +:101A200070B590F87030044613B1002380F8703020 +:101A300004F18002204601F049FA63689B68B3B95B +:101A400094F8803013F0600535D00021204601F075 +:101A50003BFD0021204601F02BFD63681B6813B19C +:101A6000062120469847062384F8703070BD204632 +:101A700098470028E4D0B4F88630A26F9A4288BF15 +:101A8000A36794F98030A56F002B4FF0300380F2EC +:101A90000381002D00F0F280092284F8702083F386 +:101AA000118800212046D4E91D23FFF76DFF002394 +:101AB00083F31188DAE794F8812003F07F0343EA87 +:101AC000022340F20232934200F0C58021D8B3F5E0 +:101AD000807F48D00DD8012B3FD0022B00F093809F +:101AE000002BB2D104F1880262670222A267E36789 +:101AF000C1E7B3F5817F00F09B80B3F5407FA4D1AF +:101B000094F88230012BA0D1B4F8883043F002035E +:101B100032E0B3F5006F4DD017D8B3F5A06F31D0D8 +:101B2000A3F5C063012B90D86368204694F8822007 +:101B30005E6894F88310B4F88430B047002884D0ED +:101B4000436863670368A3671AE0B3F5106F36D084 +:101B500040F6024293427FF478AF5C4B6367022306 +:101B6000A3670023C3E794F88230012B7FF46DAFA5 +:101B7000B4F8883023F00203A4F88830C4E91D5576 +:101B8000E56778E7B4F88030B3F5A06F0ED194F82C +:101B90008230204684F88A3001F0DAF863681B68E6 +:101BA00013B1012120469847032323700023C4E981 +:101BB0001D339CE704F18B0363670123C3E723789C +:101BC000042B10D1302383F311882046FFF7BAFE8F +:101BD00085F311880321636884F88B5021701B689A +:101BE0000BB12046984794F88230002BDED084F861 +:101BF0008B300423237063681B68002BD6D002212E +:101C000020469847D2E794F8843020461D0603F01A +:101C10000F010AD501F04CF9012804D002287FF405 +:101C200014AF2B4B9AE72B4B98E701F033F9F3E70E +:101C300094F88230002B7FF408AF94F8843013F0CE +:101C40000F01B3D01A06204602D501F055FCADE7CE +:101C500001F046FCAAE794F88230002B7FF4F5AE41 +:101C600094F8843013F00F01A0D01B06204602D553 +:101C700001F02AFC9AE701F01BFC97E7142284F894 +:101C8000702083F311882B462A4629462046FFF709 +:101C900069FE85F31188E9E65DB1152284F87020AC +:101CA00083F3118800212046D4E91D23FFF75AFE53 +:101CB000FDE60B2284F8702083F311882B462A4618 +:101CC00029462046FFF760FEE3E700BF0842000810 +:101CD000004200080442000838B590F8703004460D +:101CE000002B3ED0063BDAB20F2A34D80F2B32D865 +:101CF000DFE803F03731310822323131313131310F +:101D000031313737856FB0F886309D4214D2C368C1 +:101D10001B8AB5FBF3F203FB12556DB9302383F335 +:101D200011882B462A462946FFF72EFE85F3118897 +:101D30000A2384F870300EE0142384F870303023C6 +:101D400083F31188002320461A461946FFF70AFE3E +:101D5000002383F3118838BDC36F03B19847002374 +:101D6000E7E70021204601F0AFFB0021204601F00B +:101D70009FFB63681B6813B1062120469847062322 +:101D8000D7E7000010B590F870300446142B29D026 +:101D900017D8062B05D001D81BB110BD093B022B6B +:101DA000FBD80021204601F08FFB0021204601F0E6 +:101DB0007FFB63681B6813B1062120469847062302 +:101DC00019E0152BE9D10B2380F87030302383F311 +:101DD000118800231A461946FFF7D6FD002383F326 +:101DE0001188DAE7C3689B695B68002BD5D1C36FA4 +:101DF00003B19847002384F87030CEE7002382684F +:101E0000037503691B6899689142FBD25A680360A5 +:101E10004260106058607047002382680375036950 +:101E20001B6899689142FBD85A6803604260106051 +:101E30005860704708B50846302383F311880B7D3E +:101E4000032B05D0042B0DD02BB983F3118808BDCB +:101E50008B6900221A604FF0FF338361FFF7CEFFDA +:101E60000023F2E7D1E9003213605A60F3E7000083 +:101E7000FFF7C4BF054BD96808751868026853603E +:101E80001A600122D8600275FEF7BCBA4024002017 +:101E90000C4B30B5DD684B1C87B004460FD02B4689 +:101EA000094A684600F04EF92046FFF7E3FF009B21 +:101EB00013B1684600F050F9A86907B030BDFFF7CC +:101EC000D9FFF9E740240020351E0008044B1A68AA +:101ED000DB6890689B68984294BF0020012070479F +:101EE00040240020084B10B51C68D8682268536055 +:101EF0001A600122DC602275FFF78EFF0146204642 +:101F0000BDE81040FEF77EBA4024002038B5074CEB +:101F100001230025064907482370656001F0E2FCB3 +:101F20000223237085F3118838BD00BFA826002046 +:101F3000104200084024002000F044B9034A5168D0 +:101F400053685B1A9842FBD8704700BF001000E04E +:101F50008B600223086108468B8270478368A3F177 +:101F6000840243F8142C026943F8442C426943F874 +:101F7000402C094A43F8242CC268A3F1200043F8FE +:101F8000182C022203F80C2C002203F80B2C034A15 +:101F900043F8102C704700BF1D04000840240020A7 +:101FA00008B5FFF7DBFFBDE80840FFF761BF0000A1 +:101FB000024BDB6898610F20FFF75CBF40240020D4 +:101FC000302383F31188FFF7F3BF000008B5014603 +:101FD000302383F311880820FFF75AFF002383F38F +:101FE000118808BD064BDB6839B1426818605A6039 +:101FF000136043600420FFF74BBF4FF0FF30704782 +:10200000402400200368984206D01A68026050609D +:1020100018469961FFF72CBF7047000038B5044699 +:102020000D462068844200D138BD036823605C609F +:102030008561FFF71DFFF4E7036810B59C68A242B5 +:102040000CD85C688A600B604C60216059609968AC +:102050008A1A9A604FF0FF33836010BD121B1B6811 +:10206000ECE700000A2938BF0A2170B504460D4686 +:102070000A26601901F02EFC01F016FC041BA54293 +:1020800003D8751C04462E46F3E70A2E04D9012016 +:10209000BDE8704001F066BC70BD0000F8B5144B9F +:1020A0000D460A2A4FF00A07D96103F11001826038 +:1020B00038BF0A22416019691446016048601861FE +:1020C000A81801F0F7FB01F0EFFB431B0646A34203 +:1020D00006D37C1C28192746354601F0FBFBF2E7A6 +:1020E0000A2F04D90120BDE8F84001F03BBCF8BD3F +:1020F00040240020F8B506460D4601F0D5FB0F4AF6 +:10210000134653F8107F9F4206D12A4601463046B7 +:10211000BDE8F840FFF7C2BFD169BB68441A2C196B +:1021200028BF2C46A34202D92946FFF79BFF22462F +:1021300031460348BDE8F840FFF77EBF4024002049 +:1021400050240020C0E90323002310B45DF8044BA1 +:102150004361FFF7CFBF000010B5194C23699842C7 +:102160000DD08168D0E9003213605A609A680A4441 +:102170009A60002303604FF0FF33A36110BD026833 +:10218000234643F8102F53600022026022699A42CE +:1021900003D1BDE8104001F097BB936881680B4400 +:1021A000936001F081FB2269E1699268441AA242BE +:1021B000E4D91144BDE81040091AFFF753BF00BF2E +:1021C000402400202DE9F047DFF8BC8008F110071B +:1021D0002C4ED8F8105001F067FBD8F81C40AA68C4 +:1021E000031B9A423ED814444FF00009D5E900324F +:1021F000C8F81C4013605A60C5F80090D8F8103039 +:10220000B34201D101F060FB89F31188D5E90331B4 +:1022100028469847302383F311886B69002BD8D068 +:1022200001F042FB6A69A0EB040982464A450DD2DF +:10223000022001F097FB0022D8F81030B34208D1F9 +:1022400051462846BDE8F047FFF728BF121A22443E +:10225000F2E712EB09092946384638BF4A46FFF72C +:10226000EBFEB5E7D8F81030B34208D01444C8F8F4 +:102270001C00211AA960BDE8F047FFF7F3BEBDE8D6 +:10228000F08700BF50240020402400200020704729 +:10229000FEE70000704700004FF0FF30704700007D +:1022A00002290CD0032904D00129074818BF0020B7 +:1022B0007047032A05D8054800EBC2007047044860 +:1022C00070470020704700BFE84200083C22002011 +:1022D0009C42000870B59AB005460846144601A90C +:1022E00000F0C2F801A8FEF7F3FD431C0022C6B2BD +:1022F0005B001046C5E9003423700323023404F860 +:10230000013C01ABD1B202348E4201D81AB070BD8B +:1023100013F8011B013204F8010C04F8021CF1E768 +:1023200008B5302383F311880348FFF749FA0023E7 +:1023300083F3118808BD00BFB026002090F88030DC +:1023400003F01F02012A07D190F881200B2A03D144 +:102350000023C0E91D3315E003F06003202B08D1F2 +:10236000B0F884302BB990F88120212A03D81F2A95 +:1023700004D8FFF707BA222AEBD0FAE7034A4267EC +:1023800007228267C3670120704700BF3322002005 +:1023900007B5052917D8DFE801F019160319192028 +:1023A000302383F31188104A01210190FFF7B0FA1E +:1023B000019802210D4AFFF7ABFA0D48FFF7CCF95F +:1023C000002383F3118803B05DF804FB302383F30B +:1023D00011880748FFF796F9F2E7302383F3118855 +:1023E0000348FFF7ADF9EBE73C4200086042000804 +:1023F000B026002038B50C4D0C4C2A460C4904F18F +:102400000800FFF767FF05F1CA0204F1100009494F +:10241000FFF760FF05F5CA7204F118000649BDE830 +:102420003840FFF757BF00BF883F00203C22002004 +:102430001C420008264200083142000870B50446DC +:1024400008460D46FEF744FDC6B220460134037827 +:102450000BB9184670BD32462946FEF725FD002807 +:10246000F3D10120F6E700002DE9F84F05460C46B0 +:10247000FEF72EFD2A49C6B22846FFF7DFFF08B156 +:102480000136F6B227492846FFF7D8FF08B11036C3 +:10249000F6B2632E0DD8DFF88890DFF888A0224FBF +:1024A000DFF88CB0DFF88C802E7846B92670BDE856 +:1024B000F88F29462046BDE8F84F01F0E7BD252EEC +:1024C0002AD1072249462846FEF7EEFC50B9D8F833 +:1024D00000300735083444F8083CD8F8043044F894 +:1024E000043CE1E7082251462846FEF7DDFC98B996 +:1024F000A21C0E4B197802320909C95D02F8041CAE +:1025000013F8011B01F00F015B45C95D02F8031CC4 +:10251000F0D118340835C7E7013504F8016BC3E77B +:1025200008430008314200081943000800E8F11F81 +:102530000CE8F11F10430008BFF34F8F044B1A69DA +:102540005107FCD1D3F810215207F8D1704700BFD2 +:102550000020005208B50D4B1B78ABB9FFF7ECFF1C +:102560000B4BDA68D10704D50A4A5A6002F1883267 +:102570005A60D3F80C21D20706D5064AC3F80421C5 +:1025800002F18832C3F8042108BD00BFE6410020F3 +:10259000002000522301674508B5114B1B78F3B9A1 +:1025A000104B1A69510703D5DA6842F04002DA602D +:1025B000D3F81021520705D5D3F80C2142F0400280 +:1025C000C3F80C21FFF7B8FF064BDA6842F00102AE +:1025D000DA60D3F80C2142F00102C3F80C2108BDE7 +:1025E000E6410020002000520F289ABF00F58060CD +:1025F00040040020704700004FF400307047000096 +:10260000102070470F2808B50BD8FFF7EDFF00F535 +:1026100000330268013204D104308342F9D1012031 +:1026200008BD0020FCE700000F2838B505463FD85C +:10263000FFF782FF1F4CFFF78DFF4FF0FF33072896 +:102640006361C4F814311DD82361FFF775FF0302DD +:1026500043F02403E360E36843F08003E36023690D +:102660005A07FCD42846FFF767FFFFF7BDFF4FF47A +:10267000003100F0F5F82846FFF78EFFBDE838403E +:10268000FFF7C0BFC4F81031FFF756FFA0F10803F1 +:102690001B0243F02403C4F80C31D4F80C3143F08E +:1026A0008003C4F80C31D4F810315B07FBD4D9E7B0 +:1026B000002038BD002000522DE9F84F05460C4699 +:1026C000104645EA0203DE0602D00020BDE8F88F7E +:1026D00020F01F00DFF8BCB0DFF8BCA0FFF73AFF26 +:1026E00004EB0008444503D10120FFF755FFEDE757 +:1026F00020222946204601F0B9FC10B920352034AB +:10270000F0E72B4605F120021F68791CDDD1043368 +:102710009A42F9D105F178431B481C4EB3F5801F4E +:102720001B4B38BF184603F1F80332BFD946D146D8 +:102730001E46FFF701FF0760A5EB040C336804F1A8 +:102740001C0143F002033360231FD9F8007017F017 +:102750000507FAD153F8042F8B424CF80320F4D12B +:10276000BFF34F8FFFF7E8FE4FF0FF3320222146E3 +:1027700003602846336823F00203336001F076FCDF +:102780000028BBD03846B0E7142100520C2000527C +:1027900014200052102000521021005210B5084C95 +:1027A000237828B11BB9FFF7D5FE0123237010BD94 +:1027B000002BFCD02070BDE81040FFF7EDBE00BF3D +:1027C000E64100200244074BD2B210B5904200D13E +:1027D00010BD441C00B253F8200041F8040BE0B2D5 +:1027E000F4E700BF504000580E4B30B51C6F240476 +:1027F00005D41C6F1C671C6F44F400441C670A4C12 +:1028000002442368D2B243F480732360074B9042A2 +:1028100000D130BD441C51F8045B00B243F8205095 +:10282000E0B2F4E700440258004802585040005813 +:1028300007B5012201A90020FFF7C4FF019803B0EA +:102840005DF804FB13B50446FFF7F2FFA04205D084 +:10285000012201A900200194FFF7C6FF02B010BDBC +:102860000144BFF34F8F064B884204D3BFF34F8F11 +:10287000BFF36F8F7047C3F85C022030F4E700BFEE +:1028800000ED00E0034B1A681AB9034AD2F8D024CD +:102890001A607047E84100200040025808B5FFF771 +:1028A000F1FF024B1868C0F3806008BDE8410020CA +:1028B000EFF30983054968334A6B22F001024A634A +:1028C00083F30988002383F31188704700EF00E049 +:1028D000302080F3118862B60D4B0E4AD96821F47E +:1028E000E0610904090C0A430B49DA60D3F8FC20C3 +:1028F00042F08072C3F8FC20084AC2F8B01F116889 +:1029000041F0010111602022DA7783F8220070473C +:1029100000ED00E00003FA0555CEACC5001000E064 +:10292000302310B583F311880E4B5B6813F40063FA +:1029300014D0F1EE103AEFF309844FF08073683C45 +:10294000E361094BDB6B236684F30988FFF7BEFA6A +:1029500010B1064BA36110BD054BFBE783F3118853 +:10296000F9E700BF00ED00E000EF00E02F040008F1 +:102970003204000870B5BFF34F8FBFF36F8F1A4A50 +:102980000021C2F85012BFF34F8FBFF36F8F53690E +:1029900043F400335361BFF34F8FBFF36F8FC2F81F +:1029A0008410BFF34F8FD2F8803043F6E074C3F346 +:1029B000C900C3F34E335B0103EA0406014646EA4D +:1029C00081750139C2F86052F9D2203B13F1200F12 +:1029D000F2D1BFF34F8F536943F480335361BFF398 +:1029E0004F8FBFF36F8F70BD00ED00E0FEE700007A +:1029F000214B2248224A70B5904237D3214BC11E49 +:102A0000DA1C121A22F003028B4238BF0022002186 +:102A1000FEF766FA1C4A0023C2F88430BFF34F8FDA +:102A2000D2F8803043F6E074C3F3C900C3F34E33E9 +:102A30005B0103EA0406014646EA81750139C2F8E2 +:102A40006C52F9D2203B13F1200FF2D1BFF34F8F1C +:102A5000BFF36F8FBFF34F8FBFF36F8F0023C2F8A9 +:102A60005032BFF34F8FBFF36F8F70BD53F8041B0D +:102A700040F8041BC0E700BF04450008BC43002029 +:102A8000BC430020BC43002000ED00E0074BD3F81E +:102A9000D81021EA0001C3F8D810D3F8002122EAA7 +:102AA0000002C3F80021D3F80031704700440258F7 +:102AB00070B5D0E9244300224FF0FF359E6804EB47 +:102AC00042135101D3F80009002805DAD3F80009B0 +:102AD00040F08040C3F80009D3F8000B002805DA65 +:102AE000D3F8000B40F08040C3F8000B01326318AC +:102AF0009642C3F80859C3F8085BE0D24FF00113BF +:102B0000C4F81C3870BD0000890141F0200101614A +:102B100003699B06FCD41220FFF710BA10B50A4CCB +:102B20002046FEF7D3FE094BC4F89030084BC4F89A +:102B30009430084C2046FEF7C9FE074BC4F890308D +:102B4000064BC4F8943010BDEC4100200000084052 +:102B50005043000888420020000004405C43000805 +:102B600070B503780546012B5CD1434BD0F89040FB +:102B7000984258D1414B0E216520D3F8D82042F01D +:102B80000062C3F8D820D3F8002142F00062C3F8F5 +:102B90000021D3F80021D3F8802042F00062C3F86E +:102BA0008020D3F8802022F00062C3F88020D3F880 +:102BB0008030FEF7B7FC324BE360324BC4F800388C +:102BC0000023D5F89060C4F8003EC02323604FF482 +:102BD0000413A3633369002BFCDA01230C20336157 +:102BE000FFF7ACF93369DB07FCD41220FFF7A6F935 +:102BF0003369002BFCDA00262846A660FFF758FF51 +:102C00006B68C4F81068DB68C4F81468C4F81C6802 +:102C100083BB1D4BA3614FF0FF336361A36843F097 +:102C20000103A36070BD194B9842C9D1134B4FF0FB +:102C30008060D3F8D82042F00072C3F8D820D3F8CF +:102C4000002142F00072C3F80021D3F80021D3F82C +:102C5000802042F00072C3F88020D3F8802022F058 +:102C60000072C3F88020D3F88030FFF70FFF0E21E9 +:102C70004D209EE7064BCDE7EC4100200044025872 +:102C80004014004003002002003C30C08842002075 +:102C9000083C30C0F8B5D0F89040054600214FF010 +:102CA00000662046FFF730FFD5F8941000234FF060 +:102CB00001128F684FF0FF30C4F83438C4F81C2874 +:102CC00004EB431201339F42C2F80069C2F8006B63 +:102CD000C2F80809C2F8080BF2D20B68D5F89020A8 +:102CE000C5F89830636210231361166916F0100658 +:102CF000FBD11220FFF722F9D4F8003823F4FE6349 +:102D0000C4F80038A36943F4402343F01003A361DF +:102D10000923C4F81038C4F814380B4BEB604FF09B +:102D2000C043C4F8103B094BC4F8003BC4F8106919 +:102D3000C4F80039D5F8983003F1100243F4801339 +:102D4000C5F89820A362F8BD2C430008408000100D +:102D5000D0F8902090F88A10D2F8003823F4FE635F +:102D600043EA0113C2F80038704700002DE9F84328 +:102D700000EB8103D0F890500C468046DA680FFAD9 +:102D800081F94801166806F00306731E022B05EB55 +:102D900041134FF0000194BFB604384EC3F8101B26 +:102DA0004FF0010104F1100398BF06F1805601FABB +:102DB00003F3916998BF06F5004600293AD0578A77 +:102DC00004F15801374349016F50D5F81C180B43E3 +:102DD0000021C5F81C382B180127C3F81019A7408B +:102DE0005369611E9BB3138A928B9B08012A88BF8B +:102DF0005343D8F89820981842EA034301F140025F +:102E00002146C8F89800284605EB82025360FFF778 +:102E10007BFE08EB8900C3681B8A43EA845348346D +:102E20001E4364012E51D5F81C381F43C5F81C7889 +:102E3000BDE8F88305EB4917D7F8001B21F40041E2 +:102E4000C7F8001BD5F81C1821EA0303C0E704F1FA +:102E50003F030B4A2846214605EB83035A60FFF7E0 +:102E600053FE05EB4910D0F8003923F40043C0F8B5 +:102E70000039D5F81C3823EA0707D7E7008000108F +:102E800000040002D0F894201268C0F89820FFF7E0 +:102E90000FBE00005831D0F8903049015B5813F450 +:102EA000004004D013F4001F0CBF02200120704723 +:102EB0004831D0F8903049015B5813F4004004D0F9 +:102EC00013F4001F0CBF02200120704700EB8101AA +:102ED000CB68196A0B6813604B6853607047000039 +:102EE00000EB810330B5DD68AA691368D36019B9B6 +:102EF000402B84BF402313606B8A1468D0F8902065 +:102F00001C4402EB4110013C09B2B4FBF3F46343EF +:102F1000033323F0030343EAC44343F0C043C0F840 +:102F2000103B2B6803F00303012B0ED1D2F80838B5 +:102F300002EB411013F4807FD0F8003B14BF43F044 +:102F4000805343F00053C0F8003B02EB4112D2F82B +:102F5000003B43F00443C2F8003B30BD2DE9F04193 +:102F6000D0F8906005460C4606EB4113D3F8087B79 +:102F70003A07C3F8087B08D5D6F814381B0704D5E0 +:102F800000EB8103DB685B689847FA071FD5D6F82A +:102F90001438DB071BD505EB8403D968CCB98B69E2 +:102FA000488A5A68B2FBF0F600FB16228AB9186804 +:102FB000DA6890420DD2121AC3E90024302383F359 +:102FC000118821462846FFF78BFF84F31188BDE85E +:102FD000F081012303FA04F26B8923EA02036B8177 +:102FE000CB68002BF3D021462846BDE8F0411847B6 +:102FF00000EB81034A0170B5DD68D0F890306C6950 +:103000002668E66056BB1A444FF40020C2F8100947 +:103010002A6802F00302012A0AB20ED1D3F8080886 +:1030200003EB421410F4807FD4F8000914BF40F081 +:10303000805040F00050C4F8000903EB4212D2F86F +:10304000000940F00440C2F800090122D3F8340816 +:1030500002FA01F10143C3F8341870BD19B9402ECA +:1030600084BF4020206020681A442E8A8419013CC5 +:10307000B4FBF6F440EAC44040F00050C6E700005C +:103080002DE9F843D0F8906005460C464F0106EB59 +:103090004113D3F8088918F0010FC3F808891CD030 +:1030A000D6F81038DB0718D500EB8103D3F80CC035 +:1030B000DCF81430D3F800E0DA68964530D2A2EBA1 +:1030C0000E024FF000091A60C3F80490302383F316 +:1030D0001188FFF78DFF89F3118818F0800F1DD03C +:1030E000D6F834380126A640334217D005EB8403C6 +:1030F0000134D5F89050D3F80CC0E4B22F44DCF87A +:10310000142005EB0434D2F800E05168714514D363 +:10311000D5F8343823EA0606C5F83468BDE8F883E4 +:10312000012303FA01F2038923EA02030381DCF895 +:103130000830002BD1D09847CFE7AEEB0103BCF8A5 +:103140001000834228BF0346D7F8180980B2B3EBBA +:10315000800FE3D89068A0F1040959F8048FC4F8EF +:103160000080A0EB09089844B8F1040FF5D8184482 +:103170000B4490605360C8E72DE9F84FD0F89050A9 +:1031800004466E69AB691E4016F480586E6103D028 +:10319000BDE8F84FFEF70ABC002E12DAD5F8003E63 +:1031A0009B0705D0D5F8003E23F00303C5F8003E89 +:1031B000D5F80438204623F00103C5F80438FEF79B +:1031C00023FC370505D52046FFF772FC2046FEF7A5 +:1031D00009FCB0040CD5D5F8083813F0060FEB68DD +:1031E00023F470530CBF43F4105343F4A053EB602B +:1031F00031071BD56368DB681BB9AB6923F0080393 +:10320000AB612378052B0CD1D5F8003E9A0705D089 +:10321000D5F8003E23F00303C5F8003E2046FEF734 +:10322000F3FB6368DB680BB120469847F30200F1BB +:10323000BA80B70226D5D4F8909000274FF0010A43 +:1032400009EB4712D2F8003B03F44023B3F5802F7B +:1032500011D1D2F8003B002B0DDA62890AFA07F38C +:1032600022EA0303638104EB8703DB68DB6813B1A5 +:103270003946204698470137D4F89430FFB29B680E +:103280009F42DDD9F00619D5D4F89000026AC2F346 +:103290000A1702F00F0302F4F012B2F5802F00F0CB +:1032A000CA80B2F5402F09D104EB8303002200F558 +:1032B0008050DB681B6A974240F0B0803003D5F83D +:1032C000185835D5E90303D500212046FFF746FEFF +:1032D000AA0303D501212046FFF740FE6B0303D567 +:1032E00002212046FFF73AFE2F0303D50321204693 +:1032F000FFF734FEE80203D504212046FFF72EFE37 +:10330000A90203D505212046FFF728FE6A0203D54E +:1033100006212046FFF722FE2B0203D50721204677 +:10332000FFF71CFEEF0103D508212046FFF716FE2C +:10333000700340F1A780E90703D500212046FFF77D +:103340009FFEAA0703D501212046FFF799FE6B07D0 +:1033500003D502212046FFF793FE2F0703D5032153 +:103360002046FFF78DFEEE0603D504212046FFF729 +:1033700087FEA80603D505212046FFF781FE6906D2 +:1033800003D506212046FFF77BFE2A0603D5072139 +:103390002046FFF775FEEB0574D520460821BDE8F1 +:1033A000F84FFFF76DBED4F890904FF0000B4FF040 +:1033B000010AD4F894305FFA8BF79B689F423FF67E +:1033C00038AF09EB4713D3F8002902F44022B2F5D5 +:1033D000802F20D1D3F80029002A1CDAD3F8002945 +:1033E00042F09042C3F80029D3F80029002AFBDB01 +:1033F0003946D4F89000FFF787FB22890AFA07F3D1 +:1034000022EA0303238104EB8703DB689B6813B183 +:103410003946204698470BF1010BCAE7910701D1C5 +:10342000D0F80080072A02F101029CBF03F8018B4B +:103430004FEA18283FE704EB830300F58050DA6871 +:10344000D2F818C0DCF80820DCE9001CA1EB0C0C59 +:1034500000218F4208D1DB689B699A683A449A60E0 +:103460005A683A445A6029E711F0030F01D1D0F8A5 +:1034700000808C4501F1010184BF02F8018B4FEA05 +:103480001828E6E7BDE8F88F08B50348FFF774FE93 +:10349000BDE80840FFF744BAEC41002008B50348F6 +:1034A000FFF76AFEBDE80840FFF73ABA88420020FD +:1034B000D0F8903003EB4111D1F8003B43F40013F6 +:1034C000C1F8003B70470000D0F8903003EB411189 +:1034D000D1F8003943F40013C1F8003970470000F7 +:1034E000D0F8903003EB4111D1F8003B23F40013E6 +:1034F000C1F8003B70470000D0F8903003EB411159 +:10350000D1F8003923F40013C1F8003970470000E6 +:1035100030B50433039C0172002104FB0325C16014 +:10352000C0E90653049B0363059BC0E90000C0E9A2 +:103530000422C0E90842C0E90A11436330BD00001B +:103540000022416AC260C0E90411C0E90A226FF09A +:103550000101FEF763BD0000D0E90432934201D1BE +:10356000C2680AB9181D70470020704703691960C6 +:103570000021C2680132C260C26913448269934269 +:10358000036124BF436A0361FEF73CBD38B50446BE +:103590000D46E3683BB162690020131D1268A36207 +:1035A0001344E36207E0237A33B929462046FEF745 +:1035B00019FD0028EDDA38BD6FF00100FBE70000CF +:1035C000C368C269013BC360436913448269934283 +:1035D000436124BF436A436100238362036B03B1E9 +:1035E0001847704770B53023044683F31188866A04 +:1035F0003EB9FFF7CBFF054618B186F31188284680 +:1036000070BDA36AE26A13F8015B9342A36202D31E +:103610002046FFF7D5FF002383F31188EFE7000072 +:103620002DE9F84F04460E46174698464FF03009EC +:1036300089F311880025AA46D4F828B0BBF1000F01 +:1036400009D141462046FFF7A1FF20B18BF3118835 +:103650002846BDE8F88FD4E90A12A7EB050B521AE9 +:10366000934528BF9346BBF1400F1BD9334601F168 +:10367000400251F8040B914243F8040BF9D1A36ABC +:10368000403640354033A362D4E90A239A4202D33C +:103690002046FFF795FF8AF31188BD42D8D289F3FF +:1036A0001188C9E730465A46FDF7F4FBA36A5E4429 +:1036B0005D445B44A362E7E710B5029C04330172EA +:1036C00003FB0421C460C0E906130023C0E90A33E8 +:1036D000039B0363049BC0E90000C0E90422C0E926 +:1036E0000842436310BD0000026A6FF00101C2602E +:1036F000426AC0E904220022C0E90A22FEF78EBC19 +:10370000D0E904239A4201D1C26822B9184650F880 +:10371000043B0B60704700231846FAE7C36800219A +:10372000C2690133C36043691344826993424361B0 +:1037300024BF436A4361FEF765BC000038B5044608 +:103740000D46E3683BB1236900201A1DA262E269BD +:103750001344E36207E0237A33B929462046FEF793 +:1037600041FC0028EDDA38BD6FF00100FBE70000F6 +:1037700003691960C268013AC260C2691344826970 +:103780009342036124BF436A036100238362036B96 +:1037900003B118477047000070B530230D4604464A +:1037A000114683F31188866A2EB9FFF7C7FF10B15F +:1037B00086F3118870BDA36A1D70A36AE26A0133A3 +:1037C0009342A36204D3E16920460439FFF7D0FF96 +:1037D000002080F31188EDE72DE9F84F04460D46EF +:1037E000904699464FF0300A8AF311880026B34676 +:1037F000A76A4FB949462046FFF7A0FF20B187F3DB +:1038000011883046BDE8F88FD4E90A073A1AA8EBC8 +:103810000607974228BF1746402F1BD905F14003E2 +:1038200055F8042B9D4240F8042BF9D1A36A403689 +:103830004033A362D4E90A239A4204D3E1692046C3 +:103840000439FFF795FF8BF311884645D9D28AF3E7 +:103850001188CDE729463A46FDF71CFBA36A3D4493 +:103860003E443B44A362E5E7D0E904239A4217D1E2 +:10387000C3689BB1836A8BB1043B9B1A0ED0136063 +:10388000C368013BC360C3691A4483699A420261F9 +:1038900024BF436A036100238362012318467047F3 +:1038A0000023FBE700F024B9014B586A704700BFC2 +:1038B000000C0040034B002258631A610222DA60B8 +:1038C000704700BF000C0040014B0022DA607047D7 +:1038D000000C0040014B5863704700BF000C0040D3 +:1038E000FEE7000070B51B4B0025044686B058600B +:1038F0000E4685620163FEF7EBFF04F11003A5603D +:10390000E562C4E904334FF0FF33C4E90044C4E97D +:103910000635FFF7C9FF2B46024604F13401204665 +:10392000C4E9082380230C4A2565FEF711FB012317 +:103930000A4AE06000920375684672680192B268B4 +:10394000CDE90223064BCDE90435FEF729FB06B08D +:1039500070BD00BFA8260020684300086D43000822 +:10396000E1380008024AD36A1843D062704700BFAA +:10397000402400204B6843608B688360CB68C36041 +:103980000B6943614B6903628B6943620B68036097 +:103990007047000008B53C4B40F2FF713B48D3F83C +:1039A00088200A43C3F88820D3F8882022F4FF62D5 +:1039B00022F00702C3F88820D3F88820D3F8E0204B +:1039C0000A43C3F8E020D3F808210A43C3F80821CA +:1039D0002F4AD3F808311146FFF7CCFF00F580607D +:1039E00002F11C01FFF7C6FF00F5806002F138010B +:1039F000FFF7C0FF00F5806002F15401FFF7BAFF46 +:103A000000F5806002F17001FFF7B4FF00F58060FF +:103A100002F18C01FFF7AEFF00F5806002F1A80112 +:103A2000FFF7A8FF00F5806002F1C401FFF7A2FFD5 +:103A300000F5806002F1E001FFF79CFF00F5806077 +:103A400002F1FC01FFF796FF02F58C7100F5806032 +:103A5000FFF790FF00F018F90E4BD3F8902242F0D8 +:103A60000102C3F89022D3F8942242F00102C3F875 +:103A700094220522C3F898204FF06052C3F89C208E +:103A8000054AC3F8A02008BD0044025800000258AF +:103A90007443000800ED00E01F00080308B500F0C3 +:103AA000C7FAFEF733FA0F4BD3F8DC2042F040029E +:103AB000C3F8DC20D3F8042122F04002C3F804212B +:103AC000D3F80431084B1A6842F008021A601A68E9 +:103AD00042F004021A60FEF7D5FEBDE80840FEF78A +:103AE00089BC00BF0044025800180248704700001B +:103AF000114BD3F8E82042F00802C3F8E820D3F8CD +:103B0000102142F00802C3F810210C4AD3F81031FA +:103B1000D36B43F00803D363C722094B9A624FF07B +:103B2000FF32DA6200229A615A63DA605A60012237 +:103B30005A611A60704700BF004402580010005CD0 +:103B4000000C0040094A08B51169D3680B40D9B28E +:103B50009B076FEA0101116107D5302383F31188B8 +:103B6000FEF7EAF9002383F3118808BD000C00403A +:103B7000064BD3F8DC200243C3F8DC20D3F8042141 +:103B80001043C3F80401D3F80431704700440258CD +:103B900008B53C4B4FF0FF31D3F8802062F0004273 +:103BA000C3F88020D3F8802002F00042C3F88020C0 +:103BB000D3F88020D3F88420C3F88410D3F884206D +:103BC0000022C3F88420D3F88400D86F40F0FF406F +:103BD00040F4FF0040F4DF4040F07F00D867D86F2A +:103BE00020F0FF4020F4FF0020F4DF4020F07F00B1 +:103BF000D867D86FD3F888006FEA40506FEA50500A +:103C0000C3F88800D3F88800C0F30A00C3F888001E +:103C1000D3F88800D3F89000C3F89010D3F8900040 +:103C2000C3F89020D3F89000D3F89400C3F8941010 +:103C3000D3F89400C3F89420D3F89400D3F89800F4 +:103C4000C3F89810D3F89800C3F89820D3F89800D8 +:103C5000D3F88C00C3F88C10D3F88C00C3F88C20F8 +:103C6000D3F88C00D3F89C00C3F89C10D3F89C10B8 +:103C7000C3F89C20D3F89C30FDF778FBBDE80840E2 +:103C800000F0AEB90044025808B50122534BC3F806 +:103C90000821534BD3F8F42042F00202C3F8F42079 +:103CA000D3F81C2142F00202C3F81C210222D3F8EF +:103CB0001C314C4BDA605A689104FCD54A4A1A60B0 +:103CC00001229A60494ADA6000221A614FF44042A8 +:103CD0009A61444B9A699204FCD51A6842F4807246 +:103CE0001A603F4B1A6F12F4407F04D04FF48032B9 +:103CF0001A6700221A671A6842F001021A60384BEC +:103D00001A685007FCD500221A611A6912F03802AD +:103D1000FBD1012119604FF0804159605A67344A44 +:103D2000DA62344A1A611A6842F480321A602C4B03 +:103D30001A689103FCD51A6842F480521A601A6816 +:103D40009204FCD52C4A2D499A6200225A631963C9 +:103D500001F57C01DA6301F2E71199635A64284A9C +:103D60001A64284ADA621A6842F0A8521A601C4B98 +:103D70001A6802F02852B2F1285FF9D148229A61FC +:103D80004FF48862DA6140221A621F4ADA641F4ADD +:103D90001A651F4A5A651F4A9A6532231E4A1360E4 +:103DA000136803F00F03022BFAD10D4A136943F095 +:103DB00003031361136903F03803182BFAD14FF092 +:103DC0000050FFF7D5FE4FF08040FFF7D1FE4FF0D7 +:103DD0000040BDE80840FFF7CBBE00BF00800051A7 +:103DE000004402580048025800C000F002000001E0 +:103DF0000000FF01008890082220400063020901B2 +:103E0000470E0508DD0BBF01200000200000011057 +:103E10000910E00000010110002000524FF0B042F4 +:103E200008B5D2F8883003F00103C2F8883023B116 +:103E3000044A13680BB150689847BDE80840FEF784 +:103E40006FBD00BF3C4300204FF0B04208B5D2F830 +:103E5000883003F00203C2F8883023B1044A936823 +:103E60000BB1D0689847BDE80840FEF759BD00BFC8 +:103E70003C4300204FF0B04208B5D2F8883003F040 +:103E80000403C2F8883023B1044A13690BB15069A6 +:103E90009847BDE80840FEF743BD00BF3C43002003 +:103EA0004FF0B04208B5D2F8883003F00803C2F8EA +:103EB000883023B1044A93690BB1D0699847BDE8B3 +:103EC0000840FEF72DBD00BF3C4300204FF0B0423C +:103ED00008B5D2F8883003F01003C2F8883023B157 +:103EE000044A136A0BB1506A9847BDE80840FEF7D0 +:103EF00017BD00BF3C4300204FF0B04310B5D3F8CE +:103F0000884004F47872C3F88820A30604D5124AC6 +:103F1000936A0BB1D06A9847600604D50E4A136BBA +:103F20000BB1506B9847210604D50B4A936B0BB12C +:103F3000D06B9847E20504D5074A136C0BB1506C5F +:103F40009847A30504D5044A936C0BB1D06C9847ED +:103F5000BDE81040FEF7E4BC3C4300204FF0B04306 +:103F600010B5D3F8884004F47C42C3F88820620579 +:103F700004D5164A136D0BB1506D9847230504D52F +:103F8000124A936D0BB1D06D9847E00404D50F4AE7 +:103F9000136E0BB1506E9847A10404D50B4A936E73 +:103FA0000BB1D06E9847620404D5084A136F0BB169 +:103FB000506F9847230404D5044A936F0BB1D06F18 +:103FC0009847BDE81040FEF7ABBC00BF3C43002063 +:103FD00008B5FFF7B7FDBDE80840FEF7A1BC00003B +:103FE000062108B50846FDF79DFA06210720FDF7D2 +:103FF00099FA06210820FDF795FA06210920FDF718 +:1040000091FA06210A20FDF78DFA06211720FDF707 +:1040100089FA06212820FDF785FA09217A20FDF783 +:1040200081FA07213220BDE80840FDF77BBA000085 +:1040300008B5FFF7ADFD00F00BF8FDF745FCFDF707 +:1040400017FBFFF753FDBDE80840FFF72BBC00004E +:104050000023054A19460133102BC2E9001102F171 +:104060000802F8D1704700BF3C43002010B5013969 +:104070000244904201D1002005E0037811F8014F7D +:10408000A34201D0181B10BD0130F2E7034611F81E +:10409000012B03F8012B002AF9D1704753544D33FB +:1040A0003248373F3F3F0053544D3332483733781F +:1040B0002F3732780053544D3332483734332F374B +:1040C00035332F373530000001105A0003105900E6 +:1040D0000120580003205600100002400800024052 +:1040E0000008024000000B002800024008000240C7 +:1040F0000408024006010C00400002400800024093 +:104100000808024010020D0058000240080002405A +:104110000C08024016030E00700002400C00024022 +:104120001008024000040F00880002400C0002400A +:104130001408024006051000A00002400C000240D6 +:104140001808024010061100B80002400C0002409E +:104150001C08024016072F00100402400804024009 +:1041600020080240000838002804024008040240E9 +:1041700024080240060939004004024008040240B5 +:1041800028080240100A3A0058040240080402407D +:104190002C080240160B3B00700402400C04024045 +:1041A00030080240000C3C00880402400C0402402D +:1041B00034080240060D4400A00402400C040240F2 +:1041C00038080240100E4500B80402400C040240BA +:1041D0003C080240160F460000000000ED150008E4 +:1041E000D915000815160008011600080D1600085C +:1041F000F9150008E5150008D1150008211600087A +:10420000000000000100000000000000633000001A +:104210000C42000898240020A826002041726475F2 +:1042200050696C6F740025424F415244252D424C19 +:10423000002553455249414C250000000200000072 +:10424000000000000D1800087D1800084000400024 +:10425000583F0020683F00200200000000000000DE +:104260000300000000000000C51800080000000066 +:1042700010000000783F0020000000000100000056 +:1042800000000000EC410020010102009123000821 +:10429000A12200083D23000821230008430000005C +:1042A000A442000809024300020100C032090400D0 +:1042B0000001020201000524001001052401000193 +:1042C000042402020524060001070582030800FFFA +:1042D00009040100020A0000000705010240000075 +:1042E000070581024000000012000000F0420008B3 +:1042F00012011001020000400912415700020102A0 +:10430000030100000403090425424F4152442500E3 +:104310004E7874505834763200303132333435367A +:104320003738394142434445460000000000000050 +:10433000211A0008D91C0008851D00084000400013 +:1043400024430020244300200100000034430020C7 +:104350008000000040010000080000000001000093 +:1043600000100000080000006D61696E0069646C57 +:10437000650000005000802A00000000AAAAAAAA36 +:1043800050000024FFFF00000000000000A00A0011 +:104390000000004000000000AAAAAAAA0000000035 +:1043A000FFFF0000000000000000000010000004FB +:1043B00000000000AAAAAAAA10000004FFFF000043 +:1043C00000000000000000000000400000000000AD +:1043D000AAAAAAAA00000000FFFF00000000000037 +:1043E000000000000000000000000000AAAAAAAA25 +:1043F00000000000FFFF00000000000000000000BF +:104400000000000000000000AAAAAAAA0000000004 +:10441000FFFF00000000000000000000000000009E +:1044200000000000AAAAAAAA00000000FFFF0000E6 +:10443000000000000000000000000000000000007C +:10444000AAAAAAAA00000000FFFF000000000000C6 +:10445000000000000000000000000000AAAAAAAAB4 +:1044600000000000FFFF000000000000000000004E +:104470000000000000000000AAAAAAAA0000000094 +:10448000FFFF00000000000000000000000000002E +:1044900000000000AAAAAAAA00000000FFFF000076 +:1044A0000000000000000000870400000000000081 +:1044B00000001A0000000000FF00000000000000E3 +:1044C0009C40000883040000A7400008500400003E +:1044D000B5400008009600000000080096000000AB +:1044E0000008000004000000044300080000000071 +:1044F00000000000000000000000000000000000BC +:0445000000000000B7 +: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/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp new file mode 100644 index 0000000000000..88325f17f155c --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp @@ -0,0 +1,142 @@ +// ============================================================================= +/** + * @file CX-GBXXXCtrl.cpp + * @brief CX-GBXXX用コントロールクラス ヘッダ + * @copyright (c) 2022 Xacti Corporation + */ +// ============================================================================= + +#include "CX-GBXXXCtrl.h" +#include +#include +#include + +// ----------------------------------------------------------------------------- +/*! + * @brief CX_GBXXXCtrlコンストラクタ + */ +// ----------------------------------------------------------------------------- +CX_GBXXXCtrl::CX_GBXXXCtrl() + : m_ctx(NULL), m_dev(NULL), m_devh(NULL) +{ + uvc_error_t res = uvc_init(&m_ctx, NULL); + if (res < 0) + { + uvc_perror(res, "uvc_init"); + assert(res == 0); + } +} + +// ----------------------------------------------------------------------------- +/*! + * @brief CX_GBXXXCtrlデストラクタ + */ +// ----------------------------------------------------------------------------- +CX_GBXXXCtrl::~CX_GBXXXCtrl() +{ + uvc_exit(m_ctx); +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラオープン + * + * @param [in] callback カメラシリアル番号(NULL: Don't Care) + * + * @return オープン成功可否 + */ +// ----------------------------------------------------------------------------- +bool CX_GBXXXCtrl::Open(const char *serial) +{ + uvc_error_t res; + if ((res = uvc_find_device( + m_ctx, &m_dev, + 0x296b, 0, serial)) < 0) + { + uvc_perror(res, "uvc_find_device"); // CX-GBXXX未接続 + return false; + } + + if ((res = uvc_open(m_dev, &m_devh)) < 0) + { + uvc_perror(res, "uvc_open"); + return false; + } + + return true; +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラクローズ + */ +// ----------------------------------------------------------------------------- +void CX_GBXXXCtrl::Close() +{ + if (m_devh) + { + uvc_close(m_devh); + } + if (m_dev) + { + uvc_unref_device(m_dev); + } +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラ情報設定 + * + * @param [in] unit_id ユニットID + * @param [in] cotrol_id コントロールID + * @param [in] data データバッファ + * @param [in] length データサイズ(バイト) + * + * @return 成功可否 + */ +// ----------------------------------------------------------------------------- +bool CX_GBXXXCtrl::SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length) +{ + if (!m_devh) + { + uvc_perror(UVC_ERROR_INVALID_DEVICE, "SetCameraCtrl"); + return false; + } + + if (uvc_set_ctrl(m_devh, unit_id, cotrol_id, data, length) != length) + { + uvc_perror(UVC_ERROR_OTHER, "SetCameraCtrl"); + return false; + } + + return true; +} + +// ----------------------------------------------------------------------------- +/*! + * @brief カメラ情報取得 + * + * @param [in] unit_id ユニットID + * @param [in] cotrol_id コントロールID + * @param [out] data データバッファ + * @param [in] length データサイズ(バイト) + * + * @return 成功可否 + */ +// ----------------------------------------------------------------------------- +bool CX_GBXXXCtrl::GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length) +{ + if (!m_devh) + { + uvc_perror(UVC_ERROR_INVALID_DEVICE, "GetCameraCtrl"); + return false; + } + + if (uvc_get_ctrl(m_devh, unit_id, cotrol_id, data, length, UVC_GET_CUR) != length) + { + uvc_perror(UVC_ERROR_OTHER, "GetCameraCtrl"); + return false; + } + + return true; +} diff --git a/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h new file mode 100644 index 0000000000000..ee08e3a804a6c --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h @@ -0,0 +1,40 @@ +// ============================================================================= +/** + * @file CX-GBXXXCtrl.h + * @brief CX-GBXXX用コントロールクラス ヘッダ + * @copyright (c) 2022 Xacti Corporation + */ +// ============================================================================= + +#pragma once + +#include + +struct uvc_context; +typedef struct uvc_context uvc_context_t; +struct uvc_device; +typedef struct uvc_device uvc_device_t; +struct uvc_device_handle; +typedef struct uvc_device_handle uvc_device_handle_t; +struct uvc_frame; +typedef struct uvc_frame uvc_frame_t; + +/*! @brief CCX_GBXXX用コントロールクラス */ +class CX_GBXXXCtrl +{ +public: + CX_GBXXXCtrl(); + virtual ~CX_GBXXXCtrl(); + bool Open(const char *serial); + void Close(); + + //! カメラコマンド + bool SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length); + bool GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length); + +private: + + uvc_context_t *m_ctx; + uvc_device_t *m_dev; + uvc_device_handle_t *m_devh; +}; diff --git a/Tools/cameras_gimbals/xacti-config/Makefile b/Tools/cameras_gimbals/xacti-config/Makefile new file mode 100644 index 0000000000000..1cca5c12ccf68 --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/Makefile @@ -0,0 +1,48 @@ +################################################################################ +# Copyright (c) 2022, Xacti Corporation. All rights reserved. +# Modified by Randy Mackay +################################################################################ + +APP:= xacti-config +CC = g++ + +# Optimisation Options +# +CFLAGOPT = +CFLAGOPT += -O0 + +SRCS:= $(wildcard *.c) $(wildcard *.cpp) + +INCS:= $(wildcard *.h) + +PKGS:= x11 + +OBJS:= $(SRCS:.c=.o) +OBJS:= $(OBJS:.cpp=.o) + +CFLAGS+= -g +CFLAGS+= $(CFLAGOPT) + +LIBS+= -lm \ + -Wl,-rpath \ + -lpthread -pthread -luvc + +CFLAGS+= `pkg-config --cflags $(PKGS)` + +LIBS+= `pkg-config --libs $(PKGS)` + +all: $(APP) + +%.o: %.c $(INCS) Makefile + $(CC) -c -o $@ $(CFLAGS) $< +%.o: %.cpp $(INCS) Makefile + $(CC) -c -o $@ $(CFLAGS) $< + +$(APP): $(OBJS) Makefile + $(CC) -o $(APP) $(OBJS) $(LIBS) + +clean: + rm -rf $(OBJS) $(APP) + +exec: + ./$(APP) diff --git a/Tools/cameras_gimbals/xacti-config/README b/Tools/cameras_gimbals/xacti-config/README new file mode 100644 index 0000000000000..364e6f16d5f8b --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/README @@ -0,0 +1,23 @@ +******************** + xacti-config + README +******************** + +Install Instructions + +- download this program to your Linux/Ubuntu PC +- sudo apt-get install libusb-1.0-0-dev +- sudo apt install libuvc-dev +- make + +Execution instructions + +- sudo xacti-config option [value] +- the following options are available + --dronecan enable (value=1) or disable (value=0) dronecan parsing + --format format SD card + --help display usage + --irpalette set IR pallete (0:white hot, 1:black hot, 2:rainbow, 3:rainHC, 4:ironbow, 5:lava, 6:arctic, 7:glowbow, 8:graded fire, 9:hottest) + --msc change to mass storage class mode (for downloading from SD card) + + diff --git a/Tools/cameras_gimbals/xacti-config/main.cpp b/Tools/cameras_gimbals/xacti-config/main.cpp new file mode 100644 index 0000000000000..8977bf569c140 --- /dev/null +++ b/Tools/cameras_gimbals/xacti-config/main.cpp @@ -0,0 +1,99 @@ +#include +#include +#include +#include "CX-GBXXXCtrl.h" + +const char* this_app_str = "xacti-config"; + +// display help +void display_help() +{ + printf("Usage: sudo %s option [value]\n", this_app_str); + printf(" --dronecan\tenable (value=1) or disable (value=0) dronecan parsing\n"); + printf(" --format\tformat SD card\n"); + printf(" --help\t\tdisplay usage\n"); + printf(" --irpalette\t\tIR pallete (0:white hot, 1:black hot, 2:rainbow, 3:rainHC, 4:ironbow, 5:lava, 6:arctic, 7:glowbow, 8:graded fire, 9:hottest)\n"); + printf(" --msc\t\tchange to mass storage class mode (for downloading from SD card)\n"); +} + +int main(int argc, char **argv) +{ + // display help + if ((argc <= 1) || ((argc >= 2) && (strcmp(argv[1], "--help") == 0))) { + display_help(); + return 0; + } + + // open camera + CX_GBXXXCtrl camera_ctrl; + if (!camera_ctrl.Open(NULL)) { + printf("%s: failed to open camera\n", this_app_str); + return 1; + } + + // args_ok set to true when command line processed correctly + bool args_ok = false; + bool ret_ok = true; + + // enable DroneCAN + if ((argc >= 3) && (strcmp(argv[1], "--dronecan") == 0)) { + args_ok = true; + uint8_t enable = (strcmp(argv[2], "1") == 0); + ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x1e, &enable, sizeof(enable)); + const char* enable_or_disable_str = enable ? "enable" : "disable"; + if (ret_ok) { + printf("%s: %s DroneCAN\n", this_app_str, enable_or_disable_str); + } else { + printf("%s: failed to %s DroneCAN\n", this_app_str, enable_or_disable_str); + } + } + + // format SD card + if ((argc >= 2) && (strcmp(argv[1], "--format") == 0)) { + args_ok = true; + uint8_t format_sd = 0; + ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x15, &format_sd, sizeof(format_sd)); + if (ret_ok) { + printf("%s: formatted SD card\n", this_app_str); + } else { + printf("%s: failed format SD card\n", this_app_str); + } + } + + // IR palette + if ((argc >= 3) && (strcmp(argv[1], "--irpalette") == 0)) { + args_ok = true; + int palette_int = 0; + sscanf(argv[2], "%d", &palette_int); + uint8_t palette_uint8 = (uint8_t)palette_int; + ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x19, &palette_uint8, sizeof(palette_uint8)); + if (ret_ok) { + printf("%s: IR palette set to %d\n", this_app_str, (int)palette_uint8); + } else { + printf("%s: failed to set IR palette to %d\n", this_app_str, (int)palette_uint8); + } + } + + // change to Mass Storage Mode to allow downloading of images and videos + if ((argc >= 2) && (strcmp(argv[1], "--msc") == 0)) { + args_ok = true; + uint8_t msc_mode = 1; + ret_ok = camera_ctrl.SetCameraCtrl(0x06, 0x07, &msc_mode, sizeof(msc_mode)); + if (ret_ok) { + printf("%s: changed to mass storage mode\n", this_app_str); + } else { + printf("%s: failed to change to mass storage mode\n", this_app_str); + } + } + + // close camera + camera_ctrl.Close(); + + // display help if args could not be processed + if (!args_ok) { + display_help(); + } + + // return 0 if OK, 1 if not OK + return ret_ok ? 0 : 1; +} diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index e3219e6981219..2ceb176813455 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -114,6 +114,11 @@ elif [ ${RELEASE_CODENAME} == 'mantic' ]; then SITLCFML_VERSION="2.5" PYTHON_V="python3" PIP=pip3 +elif [ ${RELEASE_CODENAME} == 'noble' ]; then + SITLFML_VERSION="2.6" + SITLCFML_VERSION="2.6" + PYTHON_V="python3" + PIP=pip3 elif [ ${RELEASE_CODENAME} == 'groovy' ] || [ ${RELEASE_CODENAME} == 'bullseye' ]; then SITLFML_VERSION="2.5" @@ -169,7 +174,8 @@ ARM_LINUX_PKGS="g++-arm-linux-gnueabihf $INSTALL_PKG_CONFIG" if [ ${RELEASE_CODENAME} == 'bookworm' ] || [ ${RELEASE_CODENAME} == 'lunar' ] || - [ ${RELEASE_CODENAME} == 'mantic' ]; then + [ ${RELEASE_CODENAME} == 'mantic' ] || + [ ${RELEASE_CODENAME} == 'noble' ]; then # on Lunar (and presumably later releases), we install in venv, below PYTHON_PKGS+=" numpy pyparsing psutil" SITL_PKGS="python3-dev" @@ -181,7 +187,8 @@ fi if [[ $SKIP_AP_GRAPHIC_ENV -ne 1 ]]; then if [ ${RELEASE_CODENAME} == 'bookworm' ] || [ ${RELEASE_CODENAME} == 'lunar' ] || - [ ${RELEASE_CODENAME} == 'mantic' ]; then + [ ${RELEASE_CODENAME} == 'mantic' ] || + [ ${RELEASE_CODENAME} == 'noble' ]; then PYTHON_PKGS+=" matplotlib scipy opencv-python pyyaml" SITL_PKGS+=" xterm libcsfml-dev libcsfml-audio${SITLCFML_VERSION} libcsfml-dev libcsfml-graphics${SITLCFML_VERSION} libcsfml-network${SITLCFML_VERSION} libcsfml-system${SITLCFML_VERSION} libcsfml-window${SITLCFML_VERSION} libsfml-audio${SITLFML_VERSION} libsfml-dev libsfml-graphics${SITLFML_VERSION} libsfml-network${SITLFML_VERSION} libsfml-system${SITLFML_VERSION} libsfml-window${SITLFML_VERSION}" else @@ -274,7 +281,8 @@ elif [ ${RELEASE_CODENAME} == 'lunar' ]; then SITL_PKGS+=" libpython3-stdlib" # for argparse elif [ ${RELEASE_CODENAME} == 'buster' ]; then SITL_PKGS+=" libpython3-stdlib" # for argparse -elif [ ${RELEASE_CODENAME} != 'mantic' ]; then +elif [ ${RELEASE_CODENAME} != 'mantic' ] && + [ ${RELEASE_CODENAME} != 'noble' ]; then SITL_PKGS+=" python-argparse" fi @@ -293,6 +301,9 @@ if [[ $SKIP_AP_GRAPHIC_ENV -ne 1 ]]; then elif [ ${RELEASE_CODENAME} == 'mantic' ]; then SITL_PKGS+=" libgtk-3-dev libwxgtk3.2-dev " # see below + elif [ ${RELEASE_CODENAME} == 'noble' ]; then + SITL_PKGS+=" libgtk-3-dev libwxgtk3.2-dev " + # see below elif apt-cache search python-wxgtk3.0 | grep wx; then SITL_PKGS+=" python-wxgtk3.0" elif apt-cache search python3-wxgtk4.0 | grep wx; then @@ -312,7 +323,8 @@ if [[ $SKIP_AP_GRAPHIC_ENV -ne 1 ]]; then PYTHON_PKGS+=" wxpython opencv-python" SITL_PKGS+=" python3-wxgtk4.0" SITL_PKGS+=" fonts-freefont-ttf libfreetype6-dev libpng16-16 libportmidi-dev libsdl-image1.2-dev libsdl-mixer1.2-dev libsdl-ttf2.0-dev libsdl1.2-dev" # for pygame - elif [ ${RELEASE_CODENAME} == 'mantic' ]; then + elif [ ${RELEASE_CODENAME} == 'mantic' ] || + [ ${RELEASE_CODENAME} == 'noble' ]; then PYTHON_PKGS+=" wxpython opencv-python" SITL_PKGS+=" python3-wxgtk4.0" SITL_PKGS+=" fonts-freefont-ttf libfreetype6-dev libpng16-16 libportmidi-dev libsdl-image1.2-dev libsdl-mixer1.2-dev libsdl-ttf2.0-dev libsdl1.2-dev" # for pygame @@ -360,10 +372,17 @@ fi PIP_USER_ARGUMENT="--user" # create a Python venv on more recent releases: +PYTHON_VENV_PACKAGE="" if [ ${RELEASE_CODENAME} == 'bookworm' ] || [ ${RELEASE_CODENAME} == 'lunar' ] || [ ${RELEASE_CODENAME} == 'mantic' ]; then - $APT_GET install python3.11-venv + PYTHON_VENV_PACKAGE=python3.11-venv +elif [ ${RELEASE_CODENAME} == 'noble' ]; then + PYTHON_VENV_PACKAGE=python3.12-venv +fi + +if [ -n "$PYTHON_VENV_PACKAGE" ]; then + $APT_GET install $PYTHON_VENV_PACKAGE python3 -m venv $HOME/venv-ardupilot # activate it: @@ -389,7 +408,8 @@ fi if [ ${RELEASE_CODENAME} == 'bookworm' ] || [ ${RELEASE_CODENAME} == 'lunar' ] || - [ ${RELEASE_CODENAME} == 'mantic' ]; then + [ ${RELEASE_CODENAME} == 'mantic' ] || + [ ${RELEASE_CODENAME} == 'noble' ]; then # must do this ahead of wxPython pip3 run :-/ $PIP install $PIP_USER_ARGUMENT -U attrdict3 fi diff --git a/Tools/ros2/README.md b/Tools/ros2/README.md index 9832e412f999d..c6d6504517be1 100644 --- a/Tools/ros2/README.md +++ b/Tools/ros2/README.md @@ -13,6 +13,14 @@ For example `ardurover` SITL may be launched with: ros2 launch ardupilot_sitl sitl.launch.py command:=ardurover model:=rover ``` +Other launch files are included with many arguments. +Some common arguments are exposed and forwarded to the underlying process. + +For example, MAVProxy can be launched, and you can enable the `console` and `map`. +```bash +ros2 launch ardupilot_sitl sitl_mavproxy.launch.py map:=True console:=True +``` + #### `ardupilot_dds_test` A `colcon` package for testing communication between `micro_ros_agent` and the diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index 10203e148bf53..a0ea49a58ab6f 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -286,26 +286,36 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: master = LaunchConfiguration("master").perform(context) out = LaunchConfiguration("out").perform(context) sitl = LaunchConfiguration("sitl").perform(context) + console = LaunchConfiguration("console").perform(context) + map = LaunchConfiguration("map").perform(context) # Display launch arguments. print(f"command: {command}") print(f"master: {master}") print(f"sitl: {sitl}") print(f"out: {out}") + print(f"console: {console}") + print(f"map: {map}") + + cmd = [ + f"{command} ", + f"--out {out} ", + "--out ", + "127.0.0.1:14551 ", + f"--master {master} ", + f"--sitl {sitl} ", + "--non-interactive ", + ] + + if console: + cmd.append("--console ") + + if map: + cmd.append("--map ") # Create action. mavproxy_process = ExecuteProcess( - cmd=[ - [ - f"{command} ", - f"--out {out} ", - "--out ", - "127.0.0.1:14551 ", - f"--master {master} ", - f"--sitl {sitl} ", - "--non-interactive ", - ] - ], + cmd=cmd, shell=True, output="both", respawn=False, @@ -355,6 +365,16 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: default_value="127.0.0.1:5501", description="SITL output port.", ), + DeclareLaunchArgument( + "map", + default_value="False", + description="Enable MAVProxy Map.", + ), + DeclareLaunchArgument( + "console", + default_value="False", + description="Enable MAVProxy Console.", + ), ] diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index c82d184d47b5a..21fb6ee4c60f8 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -422,7 +422,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/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 3cbc8bfb885ce..102c1958204f2 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -112,7 +112,7 @@ def __init__(self, Feature('OSD', 'PLUSCODE', 'HAL_PLUSCODE_ENABLE', 'Enable PlusCode', 0, 'OSD'), Feature('OSD', 'OSD_PARAM', 'OSD_PARAM_ENABLED', 'Enable OSD param', 0, 'OSD'), Feature('OSD', 'OSD_SIDEBARS', 'HAL_OSD_SIDEBAR_ENABLE', 'Enable Scrolling Sidebars', 0, 'OSD'), - Feature('OSD', 'OSD_EXTENDED_LINK_STATS', 'AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', 'Enable OSD panels with extended link stats data', 0, "OSD,RC_CRSF"), # noqa + Feature('OSD', 'OSD_EXTENDED_LINK_STATS', 'AP_OSD_LINK_STATS_EXTENSIONS_ENABLED', 'Enable OSD panels with extended link stats data', 0, "OSD,RC_CRSF,MSP"), # noqa Feature('VTX', 'VIDEO_TX', 'AP_VIDEOTX_ENABLED', 'Enable VideoTX control', 0, None), Feature('VTX', 'SMARTAUDIO', 'AP_SMARTAUDIO_ENABLED', 'Enable SmartAudio VTX Contol', 0, "VIDEO_TX"), @@ -255,7 +255,7 @@ def __init__(self, Feature('Sensors', 'OPTICALFLOW', 'AP_OPTICALFLOW_ENABLED', 'Enable Optical Flow', 0, None), Feature('Sensors', 'OPTICALFLOW_CXOF', 'AP_OPTICALFLOW_CXOF_ENABLED', 'Enable Optical flow CXOF Sensor', 0, "OPTICALFLOW"), - Feature('Sensors', 'OPTICALFLOW_HEREFLOW', 'AP_OPTICALFLOW_HEREFLOW_ENABLED', 'Enable Optical flow HereFlow Sensor', 0, "OPTICALFLOW"), # NOQA: E501 + Feature('Sensors', 'OPTICALFLOW_HEREFLOW', 'AP_OPTICALFLOW_HEREFLOW_ENABLED', 'Enable Optical flow HereFlow Sensor', 0, "OPTICALFLOW,DroneCAN"), # NOQA: E501 Feature('Sensors', 'OPTICALFLOW_MAV', 'AP_OPTICALFLOW_MAV_ENABLED', 'Enable Optical flow MAVLink Sensor', 0, "OPTICALFLOW"), # NOQA: E501 Feature('Sensors', 'OPTICALFLOW_ONBOARD', 'AP_OPTICALFLOW_ONBOARD_ENABLED', 'Enable Optical flow ONBOARD Sensor', 0, "OPTICALFLOW"), # NOQA: E501 Feature('Sensors', 'OPTICALFLOW_PX4FLOW', 'AP_OPTICALFLOW_PX4FLOW_ENABLED', 'Enable Optical flow PX4FLOW Sensor', 0, "OPTICALFLOW"), # NOQA: E501 @@ -297,6 +297,7 @@ def __init__(self, Feature('Sensors', 'RPM_HARMONIC_NOTCH', 'AP_RPM_HARMONICNOTCH_ENABLED', 'Enable RPM Harmonic Notch sensors', 0, 'RPM,HarmonicNotches'), # noqa Feature('Sensors', 'RPM_PIN', 'AP_RPM_PIN_ENABLED', 'Enable RPM Pin-based sensors', 0, 'RPM'), Feature('Sensors', 'RPM_GENERATOR', 'AP_RPM_GENERATOR_ENABLED', 'Enable Generator RPM sensors', 0, 'RPM,GENERATOR'), + Feature('Sensors', 'RPM_DRONECAN', 'AP_RPM_DRONECAN_ENABLED', 'Enable DroneCAN-based RPM sensors', 0, 'RPM,GENERATOR,DroneCAN'), # noqa Feature('Sensors', 'TEMP', 'AP_TEMPERATURE_SENSOR_ENABLED', 'Enable Temperature Sensors', 0, None), Feature('Sensors', 'TEMP_TSYS01', 'AP_TEMPERATURE_SENSOR_TSYS01_ENABLED', 'Enable Temp Sensor - TSYS01', 0, "TEMP"), @@ -353,7 +354,8 @@ def __init__(self, Feature('GPS Drivers', 'NOVA', 'AP_GPS_NOVA_ENABLED', 'Enable NOVA GPS', 0, None), Feature('GPS Drivers', 'SBF', 'AP_GPS_SBF_ENABLED', 'Enable SBF GPS', 0, None), Feature('GPS Drivers', 'SIRF', 'AP_GPS_SIRF_ENABLED', 'Enable SiRF GPS', 0, None), - Feature('GPS Drivers', 'DroneCAN_Out', 'AP_DRONECAN_SEND_GPS', 'Enable Sending GPS from Autopilot', 0, "DroneCAN"), + Feature('GPS Drivers', 'DroneCAN_GPS_Out', 'AP_DRONECAN_SEND_GPS', 'Enable Sending GPS from Autopilot', 0, "DroneCAN"), + Feature('GPS Drivers', 'GPS_Blending', 'AP_GPS_BLENDED_ENABLED', 'Enable GPS Blending', 0, None), Feature('Airspeed Drivers', 'Analog', 'AP_AIRSPEED_ANALOG_ENABLED', 'Enable Analog Airspeed', 0, 'AIRSPEED'), diff --git a/Tools/scripts/decode_devid.py b/Tools/scripts/decode_devid.py index 04cf8b1738d95..ab484bc11715f 100755 --- a/Tools/scripts/decode_devid.py +++ b/Tools/scripts/decode_devid.py @@ -102,6 +102,7 @@ def num(s): 0x39 : "DEVTYPE_INS_BMI085", 0x3A : "DEVTYPE_INS_ICM42670", 0x3B : "DEVTYPE_INS_ICM45686", + 0x3C : "DEVTYPE_INS_SCHA63T", } baro_types = { diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 56fb8841f6900..cc9274955df70 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -191,6 +191,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('GPS_MOVING_BASELINE', r'AP_GPS_Backend::calculate_moving_base_yaw\b',), ('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',), + ('AP_GPS_BLENDED_ENABLED', r'AP_GPS::calc_blend_weights\b',), ('HAL_WITH_DSP', r'AP_HAL::DSP::find_peaks\b',), ('AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED', r'AP_InertialSensor::HarmonicNotch::update_params\b',), diff --git a/Tools/scripts/run_astyle.py b/Tools/scripts/run_astyle.py index 4e495994735b5..c92fc9079f1d6 100755 --- a/Tools/scripts/run_astyle.py +++ b/Tools/scripts/run_astyle.py @@ -26,8 +26,12 @@ def __init__(self, *, dry_run=DRY_RUN_DEFAULT): ] self.files_to_check = [ pathlib.Path(s) for s in [ + 'ArduCopter/AP_ExternalControl_Copter.cpp', + 'ArduCopter/AP_ExternalControl_Copter.h', 'libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp', 'libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h', + 'Rover/AP_ExternalControl_Rover.cpp', + 'Rover/AP_ExternalControl_Rover.h', ] ] self.dry_run = dry_run diff --git a/Tools/scripts/serial_playback.py b/Tools/scripts/serial_playback.py new file mode 100755 index 0000000000000..b7d05b8f25a56 --- /dev/null +++ b/Tools/scripts/serial_playback.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python3 +''' +playback a capture from ardupilot with timing +the file format is a sequence of: + + HEADER + DATA + +HEADER is: + uint32_t magic == 0x7fe53b04 + uint32_t time_ms + uint32_t length +''' + +import socket +import time +import struct +from argparse import ArgumentParser + +parser = ArgumentParser(description="playback a capture file with ArduPilot timing headers") + +parser.add_argument("infile", default=None, help="input file") +parser.add_argument("dest", default=None, help="TCP destination in ip:port format") +parser.add_argument("--loop", action='store_true', help="loop to start of file at EOF") +args = parser.parse_args() + +def open_socket(dest): + a = dest.split(':') + ip = a[0] + port = int(a[1]) + tcp = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + tcp.connect((ip, port)) + return tcp + +f = open(args.infile,'rb') +tcpsock = open_socket(args.dest) + +last_ms = None + +while True: + hdr_raw = f.read(12) + if len(hdr_raw) != 12: + if args.loop: + f.seek(0) + continue + print("EOF") + break + magic, t_ms, n = struct.unpack(" 0: + time.sleep(dt*0.001) + last_ms = t_ms + data = f.read(n) + if len(data) != n: + if args.loop: + f.seek(0) + continue + print("short data, EOF") + break + tcpsock.send(data) + print("Wrote %u bytes t=%.3f" % (len(data), t_ms*0.001)) diff --git a/Tools/scripts/signing/README.md b/Tools/scripts/signing/README.md index dc4032c00987f..06fe1d6527b29 100644 --- a/Tools/scripts/signing/README.md +++ b/Tools/scripts/signing/README.md @@ -12,7 +12,7 @@ firmware doesn't match any of the public keys in the bootloader. To generate a public/private key pair, run the following command: ``` - python3 -m pip install pymonocypher + python3 -m pip install pymonocypher==3.1.3.2 Tools/scripts/signing/generate_keys.py NAME ``` @@ -131,7 +131,13 @@ This opens a secure command session using your private_key.dat file to allow the securecommand getpublickeys will return the number of public keys...you will need this next securecommand removepublickeys 0 X where X is the number of public keys...this removes them ``` -Re-run the 'getpublickeys' command again to verify that all keys have been removed. + +For example, if you have a standard firmware with the 3 ArduPilot +public keys and one of your own public keys then X will be 4 in the +above command. + +Re-run the 'getpublickeys' command again to verify that all keys have +been removed. Now exit MAVProxy and build a firmware using the normal bootloader but still using the --signed-fw option: diff --git a/Tools/scripts/signing/generate_keys.py b/Tools/scripts/signing/generate_keys.py index 5da4388c308f9..38b7d38650452 100755 --- a/Tools/scripts/signing/generate_keys.py +++ b/Tools/scripts/signing/generate_keys.py @@ -9,9 +9,12 @@ try: import monocypher except ImportError: - print("Please install monocypher with: python3 -m pip install pymonocypher") + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") sys.exit(1) +if monocypher.__version__ != "3.1.3.2": + Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2") + sys.exit(1) if len(sys.argv) != 2: print("Usage: generate_keys.py BASENAME") diff --git a/Tools/scripts/signing/make_secure_bl.py b/Tools/scripts/signing/make_secure_bl.py index bd60bee3c7af0..5187b0f15d3b1 100755 --- a/Tools/scripts/signing/make_secure_bl.py +++ b/Tools/scripts/signing/make_secure_bl.py @@ -7,12 +7,6 @@ import os import base64 -try: - import monocypher -except ImportError: - print("Please install monocypher with: python3 -m pip install pymonocypher") - sys.exit(1) - # get command line arguments from argparse import ArgumentParser parser = ArgumentParser(description='make_secure_bl') diff --git a/Tools/scripts/signing/make_secure_fw.py b/Tools/scripts/signing/make_secure_fw.py index 4e916090fc227..8c8862cb62f8c 100755 --- a/Tools/scripts/signing/make_secure_fw.py +++ b/Tools/scripts/signing/make_secure_fw.py @@ -10,9 +10,13 @@ try: import monocypher except ImportError: - print("Please install monocypher with: python3 -m pip install pymonocypher") + print("Please install monocypher with: python3 -m pip install pymonocypher==3.1.3.2") sys.exit(1) +if monocypher.__version__ != "3.1.3.2": + Logs.error("must use monocypher 3.1.3.2, please run: python3 -m pip install pymonocypher==3.1.3.2") + return None + key_len = 32 sig_len = 64 sig_version = 30437 diff --git a/Tools/vagrant/initvagrant.sh b/Tools/vagrant/initvagrant.sh index acb0f482819d9..3da7d92442a17 100755 --- a/Tools/vagrant/initvagrant.sh +++ b/Tools/vagrant/initvagrant.sh @@ -22,9 +22,15 @@ echo USING VAGRANT_USER:$VAGRANT_USER cd /home/$VAGRANT_USER +IS_BENTO=0 +if [ -e /etc/update-motd.d/99-bento ]; then + IS_BENTO=1 +fi -# artful rootfs is 2GB without resize: -sudo resize2fs /dev/sda1 +# artful rootfs is 2GB without resize. Do not resize if using Bento: +if [ ! $IS_BENTO ]; then + sudo resize2fs /dev/sda1 +fi echo "calling pre-reqs script..." sudo -H -u $VAGRANT_USER /vagrant/Tools/environment_install/install-prereqs-ubuntu.sh -y diff --git a/Vagrantfile b/Vagrantfile index 9ab2a986a5a9a..e3344a75a4c9a 100644 --- a/Vagrantfile +++ b/Vagrantfile @@ -282,4 +282,25 @@ Vagrant.configure(VAGRANTFILE_API_VERSION) do |config| end mantic.vm.boot_timeout = 1200 end + + # 24.04 end of standard support Jun 2029 + # note the use of "bento" here; Ubuntu stopped providing Vagrant + # images due to Hashicorp adopting the "Business Source License". + config.vm.define "noble", autostart: false do |noble| + noble.vm.box = "bento/ubuntu-24.04" + noble.vm.provision :shell, path: "Tools/vagrant/initvagrant.sh" + noble.vm.provider "virtualbox" do |vb| + vb.name = "ArduPilot (noble)" + end + noble.vm.boot_timeout = 1200 + end + config.vm.define "noble-desktop", autostart: false do |noble| + noble.vm.box = "bento/ubuntu-24.04" + noble.vm.provision :shell, path: "Tools/vagrant/initvagrant-desktop.sh" + noble.vm.provider "virtualbox" do |vb| + vb.name = "ArduPilot (noble-desktop)" + vb.gui = true + end + noble.vm.boot_timeout = 1200 + end end diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index c68e143a112fb..5a740b5b0a4da 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -24,7 +24,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Param: SLEW_YAW // @DisplayName: Yaw target slew rate - // @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes + // @Description: Maximum rate the yaw target can be updated in RTL and Auto flight modes // @Units: cdeg/s // @Range: 500 18000 // @Increment: 100 @@ -174,7 +174,7 @@ void AC_AttitudeControl::relax_attitude_controllers() // Initialize the angular rate variables to the current rate _ang_vel_target = _ahrs.get_gyro(); - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); _ang_vel_body = _ahrs.get_gyro(); // Initialize remaining variables @@ -253,7 +253,7 @@ void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vec _attitude_target.to_euler(_euler_angle_target); // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // rotate target and normalize Quaternion attitude_desired_update; @@ -281,7 +281,7 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler if (_rate_bf_ff_enabled) { // translate the roll pitch and yaw acceleration limits to the euler axis - const Vector3f euler_accel = euler_accel_limit(_euler_angle_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); + const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration @@ -294,11 +294,11 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler _euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc); // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward - euler_rate_to_ang_vel(_euler_angle_target, _euler_rate_target, _ang_vel_target); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); // Limit the angular velocity ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); } else { // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed. _euler_angle_target.x = euler_roll_angle; @@ -333,7 +333,7 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle const float slew_yaw_max_rads = get_slew_yaw_max_rads(); if (_rate_bf_ff_enabled) { // translate the roll pitch and yaw acceleration limits to the euler axis - const Vector3f euler_accel = euler_accel_limit(_euler_angle_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); + const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); // When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler // angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration @@ -346,11 +346,11 @@ void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle } // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward - euler_rate_to_ang_vel(_euler_angle_target, _euler_rate_target, _ang_vel_target); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); // Limit the angular velocity ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max)); // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); } else { // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed. _euler_angle_target.x = euler_roll_angle; @@ -388,7 +388,7 @@ void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_c if (_rate_bf_ff_enabled) { // translate the roll pitch and yaw acceleration limits to the euler axis - const Vector3f euler_accel = euler_accel_limit(_euler_angle_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); + const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()}); // When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing // the output rate towards the input rate. @@ -397,7 +397,7 @@ void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_c _euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc); // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward - euler_rate_to_ang_vel(_euler_angle_target, _euler_rate_target, _ang_vel_target); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); } else { // When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed. // Pitch angle is restricted to +- 85.0 degrees to avoid gimbal lock discontinuities. @@ -437,7 +437,7 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, fl _ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc); // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); } else { // When feedforward is not enabled, the quaternion is calculated and is input into the target and the feedforward rate is zeroed. Quaternion attitude_target_update; @@ -473,7 +473,7 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, _ahrs.get_quat_body_to_ned(_attitude_target); _attitude_target.to_euler(_euler_angle_target); // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); _ang_vel_body = _ang_vel_target; } @@ -519,7 +519,7 @@ void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, _attitude_target.to_euler(_euler_angle_target); // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Compute the angular velocity target from the integrated rate error _attitude_ang_error.to_axis_angle(attitude_error); @@ -603,7 +603,7 @@ void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust } // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Call quaternion attitude controller attitude_controller_run_quat(); @@ -651,7 +651,7 @@ void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vect } // Convert body-frame angular velocity into euler angle derivative of desired attitude - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); // Call quaternion attitude controller attitude_controller_run_quat(); @@ -908,24 +908,25 @@ void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_m } // translates body frame acceleration limits to the euler axis -Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel) +Vector3f AC_AttitudeControl::euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel) { - float sin_phi = constrain_float(fabsf(sinf(euler_rad.x)), 0.1f, 1.0f); - float cos_phi = constrain_float(fabsf(cosf(euler_rad.x)), 0.1f, 1.0f); - float sin_theta = constrain_float(fabsf(sinf(euler_rad.y)), 0.1f, 1.0f); - float cos_theta = constrain_float(fabsf(cosf(euler_rad.y)), 0.1f, 1.0f); - - Vector3f rot_accel; - if (is_zero(euler_accel.x) || is_zero(euler_accel.y) || is_zero(euler_accel.z) || is_negative(euler_accel.x) || is_negative(euler_accel.y) || is_negative(euler_accel.z)) { - rot_accel.x = euler_accel.x; - rot_accel.y = euler_accel.y; - rot_accel.z = euler_accel.z; - } else { - rot_accel.x = euler_accel.x; - rot_accel.y = MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi); - rot_accel.z = MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta)); + if (!is_positive(euler_accel.x) || !is_positive(euler_accel.y) || !is_positive(euler_accel.z)) { + return Vector3f { euler_accel }; } - return rot_accel; + + const float phi = att.get_euler_roll(); + const float theta = att.get_euler_pitch(); + + const float sin_phi = constrain_float(fabsf(sinf(phi)), 0.1f, 1.0f); + const float cos_phi = constrain_float(fabsf(cosf(phi)), 0.1f, 1.0f); + const float sin_theta = constrain_float(fabsf(sinf(theta)), 0.1f, 1.0f); + const float cos_theta = constrain_float(fabsf(cosf(theta)), 0.1f, 1.0f); + + return Vector3f { + euler_accel.x, + MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi), + MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta)) + }; } // Sets attitude target to vehicle attitude and sets all rates to zero @@ -957,7 +958,7 @@ void AC_AttitudeControl::reset_yaw_target_and_rate(bool reset_rate) _euler_rate_target.z = 0.0f; // Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward - euler_rate_to_ang_vel(_euler_angle_target, _euler_rate_target, _ang_vel_target); + euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target); } } @@ -976,12 +977,15 @@ void AC_AttitudeControl::inertial_frame_reset() } // Convert a 321-intrinsic euler angle derivative to an angular velocity vector -void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads) +void AC_AttitudeControl::euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads) { - float sin_theta = sinf(euler_rad.y); - float cos_theta = cosf(euler_rad.y); - float sin_phi = sinf(euler_rad.x); - float cos_phi = cosf(euler_rad.x); + const float theta = att.get_euler_pitch(); + const float phi = att.get_euler_roll(); + + const float sin_theta = sinf(theta); + const float cos_theta = cosf(theta); + const float sin_phi = sinf(phi); + const float cos_phi = cosf(phi); ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z; ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z; @@ -990,12 +994,15 @@ void AC_AttitudeControl::euler_rate_to_ang_vel(const Vector3f& euler_rad, const // Convert an angular velocity vector to a 321-intrinsic euler angle derivative // Returns false if the vehicle is pitched 90 degrees up or down -bool AC_AttitudeControl::ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads) +bool AC_AttitudeControl::ang_vel_to_euler_rate(const Quaternion& att, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads) { - float sin_theta = sinf(euler_rad.y); - float cos_theta = cosf(euler_rad.y); - float sin_phi = sinf(euler_rad.x); - float cos_phi = cosf(euler_rad.x); + const float theta = att.get_euler_pitch(); + const float phi = att.get_euler_roll(); + + const float sin_theta = sinf(theta); + const float cos_theta = cosf(theta); + const float sin_phi = sinf(phi); + const float cos_phi = cosf(phi); // When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous. In this case, we just return false. if (is_zero(cos_theta)) { diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 29ec8eae60682..e4993e53abc85 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -200,11 +200,11 @@ class AC_AttitudeControl { virtual void rate_controller_run() = 0; // Convert a 321-intrinsic euler angle derivative to an angular velocity vector - void euler_rate_to_ang_vel(const Vector3f& euler_rad, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads); + void euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads); // Convert an angular velocity vector to a 321-intrinsic euler angle derivative // Returns false if the vehicle is pitched 90 degrees up or down - bool ang_vel_to_euler_rate(const Vector3f& euler_rad, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads); + bool ang_vel_to_euler_rate(const Quaternion& att, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads); // Specifies whether the attitude controller should use the square root controller in the attitude correction. // This is used during Autotune to ensure the P term is tuned without being influenced by the acceleration limit of the square root controller. @@ -326,7 +326,7 @@ class AC_AttitudeControl { void ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const; // translates body frame acceleration limits to the euler axis - Vector3f euler_accel_limit(const Vector3f &euler_rad, const Vector3f &euler_accel); + Vector3f euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel); // Calculates the body frame angular velocities to follow the target attitude void attitude_controller_run_quat(); diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 98b5df48f945c..199820a070e8a 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -361,7 +361,9 @@ void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_pass // convert angle error rotation vector into 321-intrinsic euler angle difference // NOTE: this results an an approximation linearized about the vehicle's attitude - if (ang_vel_to_euler_rate(Vector3f(_ahrs.roll, _ahrs.pitch, _ahrs.yaw), _att_error_rot_vec_rad, att_error_euler_rad)) { + Quaternion att; + _ahrs.get_quat_body_to_ned(att); + if (ang_vel_to_euler_rate(att, _att_error_rot_vec_rad, att_error_euler_rad)) { _euler_angle_target.x = wrap_PI(att_error_euler_rad.x + _ahrs.roll); _euler_angle_target.y = wrap_PI(att_error_euler_rad.y + _ahrs.pitch); _euler_angle_target.z = wrap_2PI(att_error_euler_rad.z + _ahrs.yaw); diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp index 3596d18b5dd68..05d23059dd53e 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp @@ -42,7 +42,7 @@ void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch) // Initialize the roll and yaw angular rate variables to the current rate _ang_vel_target = _ahrs.get_gyro(); - ang_vel_to_euler_rate(_euler_angle_target, _ang_vel_target, _euler_rate_target); + ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target); _ang_vel_body.x = _ahrs.get_gyro().x; _ang_vel_body.z = _ahrs.get_gyro().z; diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 79e447e471bb0..afad2ab3ffbd6 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -643,7 +643,10 @@ void AC_PosControl::update_xy_controller() // Position Controller const Vector3f &curr_pos = _inav.get_position_neu_cm(); - Vector2f vel_target = _p_pos_xy.update_all(_pos_target.x, _pos_target.y, curr_pos); + // determine the combined position of the actual position and the disturbance from system ID mode + Vector3f comb_pos = curr_pos; + comb_pos.xy() += _disturb_pos; + Vector2f vel_target = _p_pos_xy.update_all(_pos_target.x, _pos_target.y, comb_pos); // add velocity feed-forward scaled to compensate for optical flow measurement induced EKF noise vel_target *= ahrsControlScaleXY; @@ -653,7 +656,10 @@ void AC_PosControl::update_xy_controller() // Velocity Controller const Vector2f &curr_vel = _inav.get_velocity_xy_cms(); - Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), curr_vel, _dt, _limit_vector.xy()); + // determine the combined velocity of the actual velocity and the disturbance from system ID mode + Vector2f comb_vel = curr_vel; + comb_vel += _disturb_vel; + Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), comb_vel, _dt, _limit_vector.xy()); // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise accel_target *= ahrsControlScaleXY; @@ -686,6 +692,9 @@ void AC_PosControl::update_xy_controller() // update angle targets that will be passed to stabilize controller accel_to_lean_angles(_accel_target.x, _accel_target.y, _roll_target, _pitch_target); calculate_yaw_and_rate_yaw(); + + _disturb_pos.zero(); + _disturb_vel.zero(); } diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 3463da0306b8a..0681900efad95 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -398,6 +398,12 @@ class AC_PosControl /// returns true when the forward pitch demand is limited by the maximum allowed tilt bool get_fwd_pitch_is_limited() const { return _fwd_pitch_is_limited; } + + // set disturbance north + void set_disturb_pos_cm(Vector2f disturb_pos) {_disturb_pos = disturb_pos;} + + // set disturbance north + void set_disturb_vel_cms(Vector2f disturb_vel) {_disturb_vel = disturb_vel;} static const struct AP_Param::GroupInfo var_info[]; @@ -456,6 +462,8 @@ class AC_PosControl float _jerk_max_xy_cmsss; // Jerk limit of the xy kinematic path generation in cm/s^3 used to determine how quickly the aircraft varies the acceleration target float _jerk_max_z_cmsss; // Jerk limit of the z kinematic path generation in cm/s^3 used to determine how quickly the aircraft varies the acceleration target float _vel_z_control_ratio = 2.0f; // confidence that we have control in the vertical axis + Vector2f _disturb_pos; // position disturbance generated by system ID mode + Vector2f _disturb_vel; // velocity disturbance generated by system ID mode // output from controller float _roll_target; // desired roll angle in centi-degrees calculated by position controller 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 f508d59484ca7..8adc6d7c6dc4a 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -80,12 +80,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 @@ -111,6 +111,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 }; @@ -224,14 +232,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)) { @@ -248,6 +254,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); @@ -256,6 +271,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); @@ -422,7 +438,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 0d99b5e1977d5..2321d74989951 100644 --- a/libraries/AC_Avoidance/AC_Avoid.h +++ b/libraries/AC_Avoidance/AC_Avoid.h @@ -211,14 +211,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_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 69c14fc8cc730..454bf0203e1fa 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -3559,6 +3559,24 @@ bool AP_AHRS::get_location_from_home_offset(Location &loc, const Vector3p &offse return true; } +/* + get EAS to TAS scaling + */ +float AP_AHRS::get_EAS2TAS(void) const +{ + if (is_positive(state.EAS2TAS)) { + return state.EAS2TAS; + } + return 1.0; +} + +// get air density / sea level density - decreases as altitude climbs +float AP_AHRS::get_air_density_ratio(void) const +{ + const float eas2tas = get_EAS2TAS(); + return 1.0 / sq(eas2tas); +} + // singleton instance AP_AHRS *AP_AHRS::_singleton; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 3113003551444..d71912c9f58e1 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -141,10 +141,11 @@ class AP_AHRS { */ // get apparent to true airspeed ratio - float get_EAS2TAS(void) const { - return state.EAS2TAS; - } + float get_EAS2TAS(void) const; + // get air density / sea level density - decreases as altitude climbs + float get_air_density_ratio(void) const; + // return an airspeed estimate if available. return true // if we have an estimate bool airspeed_estimate(float &airspeed_ret) const; diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.cpp b/libraries/AP_AHRS/AP_AHRS_Backend.cpp index e9f692fc94c7a..0b1a75842f258 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Backend.cpp @@ -265,7 +265,7 @@ void AP_AHRS::Log_Write_Home_And_Origin() // get apparent to true airspeed ratio float AP_AHRS_Backend::get_EAS2TAS(void) { - return AP::baro().get_EAS2TAS(); + return AP::baro()._get_EAS2TAS(); } // return current vibration vector for primary IMU diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 3b27e78606518..b0535c1f2ed34 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -8,6 +8,10 @@ #define AP_AHRS_ENABLED 1 #endif +#ifndef AP_HOME_ENABLED +#define AP_HOME_ENABLED AP_AHRS_ENABLED +#endif + #ifndef AP_AHRS_BACKEND_DEFAULT_ENABLED #define AP_AHRS_BACKEND_DEFAULT_ENABLED AP_AHRS_ENABLED #endif diff --git a/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp b/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp index 92ab4357ccfec..ea3e13fef2a2c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SITL.cpp @@ -33,11 +33,8 @@ bool AP_Airspeed_SITL::get_temperature(float &temperature) // this was mostly swiped from SIM_Airspeed_DLVR: const float sim_alt = sitl->state.altitude; - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - // To Do: Add a sensor board temperature offset parameter - temperature = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + temperature = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); return true; } diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 1cafcfc6e45f9..0a416d2150e1f 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -12,7 +12,7 @@ #include #include #include -#include +#include #include "AP_Airspeed.h" @@ -131,7 +131,7 @@ void AP_Airspeed::update_calibration(uint8_t i, const Vector3f &vground, int16_t // calculate true airspeed, assuming a airspeed ratio of 1.0 float dpress = MAX(get_differential_pressure(i), 0); - float true_airspeed = sqrtf(dpress) * AP::baro().get_EAS2TAS(); + float true_airspeed = sqrtf(dpress) * AP::ahrs().get_EAS2TAS(); float zratio = state[i].calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal); @@ -177,7 +177,7 @@ void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground) vy: vground.y, vz: vground.z, diff_pressure: get_differential_pressure(primary), - EAS2TAS: AP::baro().get_EAS2TAS(), + EAS2TAS: AP::ahrs().get_EAS2TAS(), ratio: param[primary].ratio.get(), state_x: state[primary].calibration.state.x, state_y: state[primary].calibration.state.y, diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index c834d51de1f5f..5b1bd0d2f95ec 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_Arming_config.h" + +#if AP_ARMING_ENABLED + #include "AP_Arming.h" #include #include @@ -2042,3 +2046,5 @@ AP_Arming &arming() }; #pragma GCC diagnostic pop + +#endif // AP_ARMING_ENABLED diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 84bfbadc9fd98..60d0740a34ece 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -74,6 +74,10 @@ #define HAL_BARO_ALLOW_INIT_NO_BARO #endif +#ifndef AP_FIELD_ELEVATION_ENABLED +#define AP_FIELD_ELEVATION_ENABLED !defined(HAL_BUILD_AP_PERIPH) && !APM_BUILD_TYPE(APM_BUILD_ArduSub) +#endif + extern const AP_HAL::HAL& hal; // table of user settable parameters @@ -169,7 +173,7 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @Increment: 1 AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT), -#if AP_BARO_PROBE_EXTERNAL_I2C_BUSES || AP_BARO_MSP_ENABLED +#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED // @Param: _PROBE_EXT // @DisplayName: External barometers to probe // @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on BARO_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in BARO_EXT_BUS. @@ -213,13 +217,14 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @Path: AP_Baro_Wind.cpp AP_SUBGROUPINFO(sensors[1].wind_coeff, "2_WCF_", 19, AP_Baro, WindCoeff), #endif - #if BARO_MAX_INSTANCES > 2 // @Group: 3_WCF_ // @Path: AP_Baro_Wind.cpp AP_SUBGROUPINFO(sensors[2].wind_coeff, "3_WCF_", 20, AP_Baro, WindCoeff), #endif -#ifndef HAL_BUILD_AP_PERIPH +#endif // HAL_BARO_WIND_COMP_ENABLED + +#if AP_FIELD_ELEVATION_ENABLED // @Param: _FIELD_ELV // @DisplayName: field elevation // @Description: User provided field elevation in meters. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level. @@ -229,7 +234,6 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = { // @User: Advanced AP_GROUPINFO("_FIELD_ELV", 22, AP_Baro, _field_elevation, 0), #endif -#endif #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) // @Param: _ALTERR_MAX @@ -347,7 +351,7 @@ void AP_Baro::calibrate(bool save) sensors[i].calibrated = false; } else { if (save) { - float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i]); + float p0_sealevel = get_sealevel_pressure(sum_pressure[i] / count[i], _field_elevation_active); sensors[i].ground_pressure.set_and_save(p0_sealevel); } } @@ -383,7 +387,7 @@ void AP_Baro::update_calibration() } for (uint8_t i=0; i<_num_sensors; i++) { if (healthy(i)) { - float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction); + float corrected_pressure = get_sealevel_pressure(get_pressure(i) + sensors[i].p_correction, _field_elevation_active); sensors[i].ground_pressure.set(corrected_pressure); } @@ -395,71 +399,13 @@ void AP_Baro::update_calibration() // always update the guessed ground temp _guessed_ground_temperature = get_external_temperature(); - - // force EAS2TAS to recalculate - _EAS2TAS = 0; -} - -// return altitude difference in meters between current pressure and a -// given base_pressure in Pascal -float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const -{ - float temp = C_TO_KELVIN(get_ground_temperature()); - float scaling = pressure / base_pressure; - - // This is an exact calculation that is within +-2.5m of the standard - // atmosphere tables in the troposphere (up to 11,000 m amsl). - return 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active; } -// return sea level pressure where in which the current measured pressure -// at field elevation returns the same altitude under the -// 1976 standard atmospheric model -float AP_Baro::get_sealevel_pressure(float pressure) const -{ - float temp = C_TO_KELVIN(get_ground_temperature()); - float p0_sealevel; - // This is an exact calculation that is within +-2.5m of the standard - // atmosphere tables in the troposphere (up to 11,000 m amsl). - p0_sealevel = 8.651154799255761e30f*pressure*powF((769231.0f-(5000.0f*_field_elevation_active)/temp),-5.255993146184937f); - - return p0_sealevel; -} - - -// return current scale factor that converts from equivalent to true airspeed -// valid for altitudes up to 10km AMSL -// assumes standard atmosphere lapse rate -float AP_Baro::get_EAS2TAS(void) -{ - float altitude = get_altitude(); - if ((fabsf(altitude - _last_altitude_EAS2TAS) < 25.0f) && !is_zero(_EAS2TAS)) { - // not enough change to require re-calculating - return _EAS2TAS; - } - - float pressure = get_pressure(); - if (is_zero(pressure)) { - return 1.0f; - } - - // only estimate lapse rate for the difference from the ground location - // provides a more consistent reading then trying to estimate a complete - // ISA model atmosphere - float tempK = C_TO_KELVIN(get_ground_temperature()) - ISA_LAPSE_RATE * altitude; - const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK)); - if (!is_positive(eas2tas_squared)) { - return 1.0f; - } - _EAS2TAS = sqrtf(eas2tas_squared); - _last_altitude_EAS2TAS = altitude; - return _EAS2TAS; -} // return air density / sea level density - decreases as altitude climbs -float AP_Baro::get_air_density_ratio(void) +float AP_Baro::_get_air_density_ratio(void) { - const float eas2tas = get_EAS2TAS(); + const float eas2tas = _get_EAS2TAS(); if (eas2tas > 0.0f) { return 1.0f/(sq(eas2tas)); } else { @@ -928,6 +874,9 @@ void AP_Baro::update(void) corrected_pressure -= wind_pressure_correction(i); #endif altitude = get_altitude_difference(sensors[i].ground_pressure, corrected_pressure); + + // the ground pressure is references against the field elevation + altitude -= _field_elevation_active; } else if (sensors[i].type == BARO_TYPE_WATER) { //101325Pa is sea level air pressure, 9800 Pascal/ m depth in water. //No temperature or depth compensation for density of water. @@ -958,7 +907,7 @@ void AP_Baro::update(void) } } } -#ifndef HAL_BUILD_AP_PERIPH +#if AP_FIELD_ELEVATION_ENABLED update_field_elevation(); #endif @@ -1004,6 +953,7 @@ bool AP_Baro::healthy(uint8_t instance) const { */ void AP_Baro::update_field_elevation(void) { +#if AP_FIELD_ELEVATION_ENABLED const uint32_t now_ms = AP_HAL::millis(); bool new_field_elev = false; const bool armed = hal.util->get_soft_armed(); @@ -1035,16 +985,7 @@ void AP_Baro::update_field_elevation(void) update_calibration(); BARO_SEND_TEXT(MAV_SEVERITY_INFO, "Field Elevation Set: %.0fm", _field_elevation_active); } -} - -/* - call accumulate on all drivers - */ -void AP_Baro::accumulate(void) -{ - for (uint8_t i=0; i<_num_drivers; i++) { - drivers[i]->accumulate(); - } +#endif } @@ -1130,7 +1071,7 @@ bool AP_Baro::arming_checks(size_t buflen, char *buffer) const if (_alt_error_max > 0 && gps.status() >= AP_GPS::GPS_Status::GPS_OK_FIX_3D) { const float alt_amsl = gps.location().alt*0.01; // note the addition of _field_elevation_active as this is subtracted in get_altitude_difference() - const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure()) + _field_elevation_active; + const float alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure()); const float error = fabsf(alt_amsl - alt_pressure); if (error > _alt_error_max) { hal.util->snprintf(buffer, buflen, "GPS alt error %.0fm (see BARO_ALTERR_MAX)", error); diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 4b1055fff9221..cfe20eed013dc 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -87,10 +87,6 @@ class AP_Baro // get pressure correction in Pascal. Divide by 100 for millibars or hectopascals float get_pressure_correction(void) const { return get_pressure_correction(_primary); } float get_pressure_correction(uint8_t instance) const { return sensors[instance].p_correction; } - - // accumulate a reading on sensors. Some backends without their - // own thread or a timer may need this. - void accumulate(void); // calibrate the barometer. This must be called on startup if the // altitude/climb_rate/acceleration interfaces are ever used @@ -105,22 +101,51 @@ class AP_Baro float get_altitude(void) const { return get_altitude(_primary); } float get_altitude(uint8_t instance) const { return sensors[instance].altitude; } + // get altitude above mean sea level + float get_altitude_AMSL(uint8_t instance) const { return get_altitude(instance) + _field_elevation_active; } + float get_altitude_AMSL(void) const { return get_altitude_AMSL(_primary); } + // returns which i2c bus is considered "the" external bus uint8_t external_bus() const { return _ext_bus; } + // Atmospheric Model Functions + static float geometric_alt_to_geopotential(float alt); + static float geopotential_alt_to_geometric(float alt); + + float get_temperature_from_altitude(float alt) const; + float get_altitude_from_pressure(float pressure) const; + + // EAS2TAS for SITL + static float get_EAS2TAS_for_alt_amsl(float alt_amsl); + + // lookup expected pressure for a given altitude. Used for SITL backend + static void get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K); + + // lookup expected temperature in degrees C for a given altitude. Used for SITL backend + static float get_temperatureC_for_alt_amsl(const float alt_amsl); + + // lookup expected pressure in Pa for a given altitude. Used for SITL backend + static float get_pressure_for_alt_amsl(const float alt_amsl); + + // get air density for SITL + static float get_air_density_for_alt_amsl(float alt_amsl); + // get altitude difference in meters relative given a base // pressure in Pascal float get_altitude_difference(float base_pressure, float pressure) const; // get sea level pressure relative to 1976 standard atmosphere model // pressure in Pascal - float get_sealevel_pressure(float pressure) const; + float get_sealevel_pressure(float pressure, float altitude) const; - // get scale factor required to convert equivalent to true airspeed - float get_EAS2TAS(void); + // get scale factor required to convert equivalent to true + // airspeed. This should only be used to update the AHRS value + // once per loop. Please use AP::ahrs().get_EAS2TAS() + float _get_EAS2TAS(void) const; // get air density / sea level density - decreases as altitude climbs - float get_air_density_ratio(void); + // please use AP::ahrs()::get_air_density_ratio() + float _get_air_density_ratio(void); // get current climb rate in meters/s. A positive number means // going up @@ -172,9 +197,6 @@ class AP_Baro // get baro drift amount float get_baro_drift_offset(void) const { return _alt_offset_active; } - // simple atmospheric model - static void SimpleAtmosphere(const float alt, float &sigma, float &delta, float &theta); - // simple underwater atmospheric model static void SimpleUnderWaterAtmosphere(float alt, float &rho, float &delta, float &theta); @@ -287,8 +309,6 @@ class AP_Baro uint32_t _field_elevation_last_ms; AP_Int8 _primary_baro; // primary chosen by user AP_Int8 _ext_bus; // bus number for external barometer - float _last_altitude_EAS2TAS; - float _EAS2TAS; float _external_temperature; uint32_t _last_external_temperature_ms; DerivativeFilterFloat_Size7 _climb_rate_filter; @@ -327,6 +347,14 @@ class AP_Baro void Write_Baro_instance(uint64_t time_us, uint8_t baro_instance); void update_field_elevation(); + + // atmosphere model functions + float get_altitude_difference_extended(float base_pressure, float pressure) const; + float get_EAS2TAS_extended(float pressure) const; + static float get_temperature_by_altitude_layer(float alt, int8_t idx); + + float get_altitude_difference_simple(float base_pressure, float pressure) const; + float get_EAS2TAS_simple(float altitude, float pressure) const; }; namespace AP { diff --git a/libraries/AP_Baro/AP_Baro_Backend.h b/libraries/AP_Baro/AP_Baro_Backend.h index 94b155e4836bd..343bacf31f62f 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.h +++ b/libraries/AP_Baro/AP_Baro_Backend.h @@ -12,11 +12,6 @@ class AP_Baro_Backend // data to the frontend virtual void update() = 0; - // accumulate function. This is used for backends that don't use a - // timer, and need to be called regularly by the main code to - // trigger them to read the sensor - virtual void accumulate(void) {} - void backend_update(uint8_t instance); // Check that the baro valid by using a mean filter. diff --git a/libraries/AP_Baro/AP_Baro_HIL.cpp b/libraries/AP_Baro/AP_Baro_HIL.cpp index 985133e0b8a1d..1442635a0ceaa 100644 --- a/libraries/AP_Baro/AP_Baro_HIL.cpp +++ b/libraries/AP_Baro/AP_Baro_HIL.cpp @@ -8,33 +8,6 @@ extern const AP_HAL::HAL& hal; // ========================================================================== // based on tables.cpp from http://www.pdas.com/atmosdownload.html -/* - Compute the temperature, density, and pressure in the standard atmosphere - Correct to 20 km. Only approximate thereafter. -*/ -void AP_Baro::SimpleAtmosphere( - const float alt, // geometric altitude, km. - float& sigma, // density/sea-level standard density - float& delta, // pressure/sea-level standard pressure - float& theta) // temperature/sea-level standard temperature -{ - const float REARTH = 6369.0f; // radius of the Earth (km) - const float GMR = 34.163195f; // gas constant - float h=alt*REARTH/(alt+REARTH); // geometric to geopotential altitude - - if (h < 11.0f) { - // Troposphere - theta = (SSL_AIR_TEMPERATURE - 6.5f * h) / SSL_AIR_TEMPERATURE; - delta = powf(theta, GMR / 6.5f); - } else { - // Stratosphere - theta = 216.65f / SSL_AIR_TEMPERATURE; - delta = 0.2233611f * expf(-GMR * (h - 11.0f) / 216.65f); - } - - sigma = delta/theta; -} - void AP_Baro::SimpleUnderWaterAtmosphere( float alt, // depth, km. float& rho, // density/sea-level diff --git a/libraries/AP_Baro/AP_Baro_Logging.cpp b/libraries/AP_Baro/AP_Baro_Logging.cpp index 91c622aaa0f20..e0e38f9becf89 100644 --- a/libraries/AP_Baro/AP_Baro_Logging.cpp +++ b/libraries/AP_Baro/AP_Baro_Logging.cpp @@ -13,6 +13,7 @@ void AP_Baro::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance) time_us : time_us, instance : baro_instance, altitude : get_altitude(baro_instance), + altitude_AMSL : get_altitude_AMSL(baro_instance), pressure : get_pressure(baro_instance), temperature : (int16_t)(get_temperature(baro_instance) * 100 + 0.5f), climbrate : get_climb_rate(), diff --git a/libraries/AP_Baro/AP_Baro_SITL.cpp b/libraries/AP_Baro/AP_Baro_SITL.cpp index 9b41e336459d7..861674360ea6e 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.cpp +++ b/libraries/AP_Baro/AP_Baro_SITL.cpp @@ -66,7 +66,11 @@ void AP_Baro_SITL::_timer() return; } - sim_alt += _sitl->baro[_instance].drift * now * 0.001f; + const auto drift_delta_t_ms = now - last_drift_delta_t_ms; + last_drift_delta_t_ms = now; + total_alt_drift += _sitl->baro[_instance].drift * drift_delta_t_ms * 0.001f; + + sim_alt += total_alt_drift; sim_alt += _sitl->baro[_instance].noise * rand_float(); // add baro glitch @@ -114,12 +118,9 @@ void AP_Baro_SITL::_timer() } #if !APM_BUILD_TYPE(APM_BUILD_ArduSub) - float sigma, delta, theta; - - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - float p = SSL_AIR_PRESSURE * delta; - float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); - + float p, T_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, T_K); + float T = KELVIN_TO_C(T_K); temperature_adjustment(p, T); #else float rho, delta, theta; @@ -139,7 +140,7 @@ void AP_Baro_SITL::_timer() // unhealthy if baro is turned off or beyond supported instances bool AP_Baro_SITL::healthy(uint8_t instance) { - return !_sitl->baro[instance].disable; + return _last_sample_time != 0 && !_sitl->baro[instance].disable; } // Read the sensor @@ -185,7 +186,7 @@ float AP_Baro_SITL::wind_pressure_correction(uint8_t instance) error += bp.wcof_zn * sqz; } - return error * 0.5 * SSL_AIR_DENSITY * AP::baro().get_air_density_ratio(); + return error * 0.5 * SSL_AIR_DENSITY * AP::baro()._get_air_density_ratio(); } #endif // AP_SIM_BARO_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_SITL.h b/libraries/AP_Baro/AP_Baro_SITL.h index 68ba04d016ac0..7d724aeaebfa9 100644 --- a/libraries/AP_Baro/AP_Baro_SITL.h +++ b/libraries/AP_Baro/AP_Baro_SITL.h @@ -48,5 +48,7 @@ class AP_Baro_SITL : public AP_Baro_Backend { float _recent_press; float _last_altitude; + uint32_t last_drift_delta_t_ms; // allows for integration of drift over time + float total_alt_drift; // integrated altitude drift in metres }; #endif // AP_SIM_BARO_ENABLED diff --git a/libraries/AP_Baro/AP_Baro_Wind.cpp b/libraries/AP_Baro/AP_Baro_Wind.cpp index 17ad6b12dda04..67b33e6a65a5f 100644 --- a/libraries/AP_Baro/AP_Baro_Wind.cpp +++ b/libraries/AP_Baro/AP_Baro_Wind.cpp @@ -76,15 +76,17 @@ float AP_Baro::wind_pressure_correction(uint8_t instance) return 0; } + auto &ahrs = AP::ahrs(); + // correct for static pressure position errors Vector3f airspeed_vec_bf; - if (!AP::ahrs().airspeed_vector_true(airspeed_vec_bf)) { + if (!ahrs.airspeed_vector_true(airspeed_vec_bf)) { return 0; } float error = 0.0; - const float kp = 0.5 * SSL_AIR_DENSITY * get_air_density_ratio(); + const float kp = 0.5 * SSL_AIR_DENSITY * ahrs.get_air_density_ratio(); const float sqxp = sq(airspeed_vec_bf.x) * kp; const float sqyp = sq(airspeed_vec_bf.y) * kp; const float sqzp = sq(airspeed_vec_bf.z) * kp; diff --git a/libraries/AP_Baro/AP_Baro_atmosphere.cpp b/libraries/AP_Baro/AP_Baro_atmosphere.cpp new file mode 100644 index 0000000000000..63667432e8f45 --- /dev/null +++ b/libraries/AP_Baro/AP_Baro_atmosphere.cpp @@ -0,0 +1,362 @@ +#include "AP_Baro.h" +#include + +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* 1976 U.S. Standard Atmosphere: https://ntrs.nasa.gov/api/citations/19770009539/downloads/19770009539.pdf?attachment=true + +The US Standard Atmosphere defines the atmopshere in terms of whether the temperature is an iso-thermal or gradient layer. +Ideal gas laws apply thus P = rho * R_specific * T : P = pressure, rho = density, R_specific = air gas constant, T = temperature + +Note: the 1976 model is the same as the 1962 US Standard Atomsphere up to 51km. +R_universal: the universal gas constant is slightly off in the 1976 model and thus R_specific is different than today's value + +*/ + +/* Model Constants +R_universal = 8.31432e-3; // Universal gas constant (J/(kmol-K)) incorrect to the redefined 2019 value of 8.31446261815324 J⋅K−1⋅mol−1 +M_air = (0.78084 * 28.0134 + 0.209476 * 31.9988 + 9.34e-3 * 39.948 + 3.14e-4 * 44.00995 + 1.818e-5 * 20.183 + 5.24E-6 * 4.0026 + 1.14E-6 * 83.8 + 8.7E-7 * 131.30 + 2E-6 * 16.04303 + 5E-7 * 2.01594) * 1E-3; (kg/mol) +M_air = 28.9644 // Molecular weight of air (kg/kmol) see page 3 +R_specific = 287.053072 // air specifc gas constant (J⋅kg−1⋅K−1), R_universal / M_air; +gama = 1.4; // specific heat ratio of air used to determine the speed of sound + +R0 = 6356.766E3; // Earth's radius (in m) +g0 = 9.80665; // gravity (m/s^2) + +Sea-Level Constants +H_asml = 0 meters +T0 = 288.150 K +P0 = 101325 Pa +rho0 = 1.2250 kg/m^3 +T0_slope = -6.5E-3 (K/m') + +The tables list altitudes -5 km to 0 km using the same equations as 0 km to 11 km. +*/ + +#ifndef AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED +// default to using the extended functions when doing double precision EKF (which implies more flash space and faster MCU) +// this allows for using the simple model with the --ekf-single configure option +#define AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED HAL_WITH_EKF_DOUBLE +#endif + +/* + return altitude difference in meters between current pressure and a + given base_pressure in Pascal. This is a simple atmospheric model + good to about 11km AMSL. +*/ +float AP_Baro::get_altitude_difference_simple(float base_pressure, float pressure) const +{ + float ret; + float temp_K = C_TO_KELVIN(get_ground_temperature()); + float scaling = pressure / base_pressure; + + // This is an exact calculation that is within +-2.5m of the standard + // atmosphere tables in the troposphere (up to 11,000 m amsl). + ret = 153.8462f * temp_K * (1.0f - expf(0.190259f * logf(scaling))); + + return ret; +} + +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED + +/* + Note parameters are as defined in the 1976 model. + These are slightly different from the ones in definitions.h +*/ +static const float radius_earth = 6356.766E3; // Earth's radius (in m) +static const float R_specific = 287.053072; // air specifc gas constant (J⋅kg−1⋅K−1) in 1976 model, R_universal / M_air; + +static const struct { + float amsl_m; // geopotential height above mean sea-level (km') + float temp_K; // Temperature (K) + float pressure_Pa; // Pressure (Pa) + float density; // Density (Pa/kg) + float temp_lapse; // Temperature gradients rates (K/m'), see page 3 +} atmospheric_1976_consts[] = { + { -5000, 320.650, 177687, 1.930467, -6.5E-3 }, + { 11000, 216.650, 22632.1, 0.363918, 0 }, + { 20000, 216.650, 5474.89, 8.80349E-2, 1E-3 }, + { 32000, 228.650, 868.019, 1.32250E-2, 2.8E-3 }, + { 47000, 270.650, 110.906, 1.42753E-3, 0 }, + { 51000, 270.650, 66.9389, 8.61606E-4, -2.8E-3 }, + { 71000, 214.650, 3.95642, 6.42110E-5, -2.0E-3 }, + { 84852, 186.946, 0.37338, 6.95788E-6, 0 }, +}; + +/* + find table entry given geopotential altitude in meters. This returns at least 1 + */ +static uint8_t find_atmosphere_layer_by_altitude(float alt_m) +{ + for (uint8_t idx = 1; idx < ARRAY_SIZE(atmospheric_1976_consts); idx++) { + if(alt_m < atmospheric_1976_consts[idx].amsl_m) { + return idx - 1; + } + } + + // Over the largest altitude return the last index + return ARRAY_SIZE(atmospheric_1976_consts) - 1; +} + +/* + find table entry given pressure (Pa). This returns at least 1 + */ +static uint8_t find_atmosphere_layer_by_pressure(float pressure) +{ + for (uint8_t idx = 1; idx < ARRAY_SIZE(atmospheric_1976_consts); idx++) { + if (atmospheric_1976_consts[idx].pressure_Pa < pressure) { + return idx - 1; + } + } + + // pressure is less than the smallest pressure return the last index + return ARRAY_SIZE(atmospheric_1976_consts) - 1; + +} + +// Convert geopotential altitude to geometric altitude +// +float AP_Baro::geopotential_alt_to_geometric(float alt) +{ + return (radius_earth * alt) / (radius_earth - alt); +} + +float AP_Baro::geometric_alt_to_geopotential(float alt) +{ + return (radius_earth * alt) / (radius_earth + alt); +} + +/* + Compute expected temperature for a given geometric altitude and altitude layer. +*/ +float AP_Baro::get_temperature_from_altitude(float alt) const +{ + alt = geometric_alt_to_geopotential(alt); + const uint8_t idx = find_atmosphere_layer_by_altitude(alt); + return get_temperature_by_altitude_layer(alt, idx); +} + +/* + Compute expected temperature for a given geopotential altitude and altitude layer. +*/ +float AP_Baro::get_temperature_by_altitude_layer(float alt, int8_t idx) +{ + if (is_zero(atmospheric_1976_consts[idx].temp_lapse)) { + return atmospheric_1976_consts[idx].temp_K; + } + return atmospheric_1976_consts[idx].temp_K + atmospheric_1976_consts[idx].temp_lapse * (alt - atmospheric_1976_consts[idx].amsl_m); +} + +/* + return geometric altitude (m) given a pressure (Pa) +*/ +float AP_Baro::get_altitude_from_pressure(float pressure) const +{ + const uint8_t idx = find_atmosphere_layer_by_pressure(pressure); + const float pressure_ratio = pressure / atmospheric_1976_consts[idx].pressure_Pa; + + // Pressure ratio is nonsensical return an error?? + if (!is_positive(pressure_ratio)) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return get_altitude_AMSL(); + } + + float alt; + const float temp_slope = atmospheric_1976_consts[idx].temp_lapse; + if (is_zero(temp_slope)) { // Iso-thermal layer + const float fac = -(atmospheric_1976_consts[idx].temp_K * R_specific) / GRAVITY_MSS; + alt = atmospheric_1976_consts[idx].amsl_m + fac * logf(pressure_ratio); + } else { // Gradient temperature layer + const float fac = -(temp_slope * R_specific) / GRAVITY_MSS; + alt = atmospheric_1976_consts[idx].amsl_m + (atmospheric_1976_consts[idx].temp_K / atmospheric_1976_consts[idx].temp_lapse) * (powf(pressure_ratio, fac) - 1); + } + + return geopotential_alt_to_geometric(alt); +} + +/* + Compute expected pressure and temperature for a given geometric altitude. Used for SITL +*/ +void AP_Baro::get_pressure_temperature_for_alt_amsl(float alt_amsl, float &pressure, float &temperature_K) +{ + alt_amsl = geometric_alt_to_geopotential(alt_amsl); + + const uint8_t idx = find_atmosphere_layer_by_altitude(alt_amsl); + const float temp_slope = atmospheric_1976_consts[idx].temp_lapse; + temperature_K = get_temperature_by_altitude_layer(alt_amsl, idx); + + // Previous versions used the current baro temperature instead of an estimate we could try to incorporate this??? non-standard atmosphere + // const float temp = get_temperature(); + + if (is_zero(temp_slope)) { // Iso-thermal layer + const float fac = expf(-GRAVITY_MSS / (temperature_K * R_specific) * (alt_amsl - atmospheric_1976_consts[idx].amsl_m)); + pressure = atmospheric_1976_consts[idx].pressure_Pa * fac; + } else { // Gradient temperature layer + const float fac = GRAVITY_MSS / (temp_slope * R_specific); + const float temp_ratio = temperature_K / atmospheric_1976_consts[idx].temp_K; // temperature ratio [unitless] + pressure = atmospheric_1976_consts[idx].pressure_Pa * powf(temp_ratio, -fac); + } +} + +/* + return air density (kg/m^3), given geometric altitude (m) +*/ +float AP_Baro::get_air_density_for_alt_amsl(float alt_amsl) +{ + alt_amsl = geometric_alt_to_geopotential(alt_amsl); + + const uint8_t idx = find_atmosphere_layer_by_altitude(alt_amsl); + const float temp_slope = atmospheric_1976_consts[idx].temp_lapse; + const float temp = get_temperature_by_altitude_layer(alt_amsl, idx); + // const float temp = get_temperature(); + + float rho; + if (is_zero(temp_slope)) { // Iso-thermal layer + const float fac = expf(-GRAVITY_MSS / (temp * R_specific) * (alt_amsl - atmospheric_1976_consts[idx].amsl_m)); + rho = atmospheric_1976_consts[idx].density * fac; + } else { // Gradient temperature layer + const float fac = GRAVITY_MSS / (temp_slope * R_specific); + const float temp_ratio = temp / atmospheric_1976_consts[idx].temp_K; // temperature ratio [unitless] + rho = atmospheric_1976_consts[idx].density * powf(temp_ratio, -(fac + 1)); + } + return rho; +} + +/* + return current scale factor that converts from equivalent to true airspeed +*/ +float AP_Baro::get_EAS2TAS_extended(float altitude) const +{ + float density = get_air_density_for_alt_amsl(altitude); + if (!is_positive(density)) { + // above this height we are getting closer to spacecraft territory... + const uint8_t table_size = ARRAY_SIZE(atmospheric_1976_consts); + density = atmospheric_1976_consts[table_size-1].density; + } + return sqrtf(SSL_AIR_DENSITY / density); +} + +/* + Given the geometric altitude (m) + return scale factor that converts from equivalent to true airspeed + used by SITL only +*/ +float AP_Baro::get_EAS2TAS_for_alt_amsl(float alt_amsl) +{ + const float density = get_air_density_for_alt_amsl(alt_amsl); + return sqrtf(SSL_AIR_DENSITY / MAX(0.00001,density)); +} + +#endif // AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED || AP_SIM_ENABLED + +/* + return geometric altitude difference in meters between current pressure and a + given base_pressure in Pascal. +*/ +float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const +{ +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED + const float alt1 = get_altitude_from_pressure(base_pressure); + const float alt2 = get_altitude_from_pressure(pressure); + return alt2 - alt1; +#else + return get_altitude_difference_simple(base_pressure, pressure); +#endif +} + +/* + return current scale factor that converts from equivalent to true airspeed + valid for altitudes up to 11km AMSL + assumes USA 1976 standard atmosphere lapse rate +*/ +float AP_Baro::get_EAS2TAS_simple(float altitude, float pressure) const +{ + if (is_zero(pressure)) { + return 1.0f; + } + + // only estimate lapse rate for the difference from the ground location + // provides a more consistent reading then trying to estimate a complete + // ISA model atmosphere + float tempK = C_TO_KELVIN(get_ground_temperature()) - ISA_LAPSE_RATE * altitude; + const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK)); + if (!is_positive(eas2tas_squared)) { + return 1.0f; + } + return sqrtf(eas2tas_squared); +} + +/* + return current scale factor that converts from equivalent to true airspeed +*/ +float AP_Baro::_get_EAS2TAS(void) const +{ + const float altitude = get_altitude_AMSL(); + +#if AP_BARO_1976_STANDARD_ATMOSPHERE_ENABLED + return get_EAS2TAS_extended(altitude); +#else + // otherwise use function + return get_EAS2TAS_simple(altitude, get_pressure()); +#endif +} + +// lookup expected temperature in degrees C for a given altitude. Used for SITL backend +float AP_Baro::get_temperatureC_for_alt_amsl(const float alt_amsl) +{ + float pressure, temp_K; + get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K); + return KELVIN_TO_C(temp_K); +} + +// lookup expected pressure in Pa for a given altitude. Used for SITL backend +float AP_Baro::get_pressure_for_alt_amsl(const float alt_amsl) +{ + float pressure, temp_K; + get_pressure_temperature_for_alt_amsl(alt_amsl, pressure, temp_K); + return pressure; +} + +/* + return sea level pressure given a current altitude and pressure reading + this is the pressure p0 such that + get_altitude_difference(p0, pressure) == altitude + this function is used during calibration +*/ +float AP_Baro::get_sealevel_pressure(float pressure, float altitude) const +{ + const float min_pressure = 0.01; + const float max_pressure = 1e6; + float p0 = pressure; + /* + use a simple numerical gradient descent method so we don't need + the inverse function. This typically converges in about 5 steps, + we limit it to 20 steps to prevent possible high CPU usage + */ + uint16_t count = 20; + while (count--) { + const float delta = 0.1; + const float err1 = get_altitude_difference(p0, pressure) - altitude; + const float err2 = get_altitude_difference(p0+delta, pressure) - altitude; + const float dalt = err2 - err1; + if (fabsf(err1) < 0.01) { + break; + } + p0 -= err1 * delta / dalt; + p0 = constrain_float(p0, min_pressure, max_pressure); + } + return p0; +} diff --git a/libraries/AP_Baro/AP_Baro_config.h b/libraries/AP_Baro/AP_Baro_config.h index 0da6757a73384..68e7a4fdab60d 100644 --- a/libraries/AP_Baro/AP_Baro_config.h +++ b/libraries/AP_Baro/AP_Baro_config.h @@ -89,3 +89,7 @@ #ifndef AP_BARO_PROBE_EXTERNAL_I2C_BUSES #define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 1 #endif + +#ifndef AP_BARO_PROBE_EXT_PARAMETER_ENABLED +#define AP_BARO_PROBE_EXT_PARAMETER_ENABLED AP_BARO_PROBE_EXTERNAL_I2C_BUSES || AP_BARO_MSP_ENABLED +#endif diff --git a/libraries/AP_Baro/LogStructure.h b/libraries/AP_Baro/LogStructure.h index 791cf33a55a50..d67b6be3c4b78 100644 --- a/libraries/AP_Baro/LogStructure.h +++ b/libraries/AP_Baro/LogStructure.h @@ -11,6 +11,7 @@ // @Field: TimeUS: Time since system startup // @Field: I: barometer sensor instance number // @Field: Alt: calculated altitude +// @Field: AltAMSL: altitude AMSL // @Field: Press: measured atmospheric pressure // @Field: Temp: measured atmospheric temperature // @Field: CRt: derived climb rate from primary barometer @@ -23,6 +24,7 @@ struct PACKED log_BARO { uint64_t time_us; uint8_t instance; float altitude; + float altitude_AMSL; float pressure; int16_t temperature; float climbrate; @@ -51,10 +53,10 @@ struct PACKED log_BARD { #define LOG_STRUCTURE_FROM_BARO \ { LOG_BARO_MSG, sizeof(log_BARO), \ "BARO", \ - "Q" "B" "f" "f" "c" "f" "I" "f" "f" "B", \ - "TimeUS," "I," "Alt," "Press," "Temp," "CRt," "SMS," "Offset," "GndTemp," "Health", \ - "s" "#" "m" "P" "O" "n" "s" "m" "O" "-", \ - "F" "-" "0" "0" "B" "0" "C" "?" "0" "-", \ + "Q" "B" "f" "f" "f" "c" "f" "I" "f" "f" "B", \ + "TimeUS," "I," "Alt," "AltAMSL," "Press," "Temp," "CRt," "SMS," "Offset," "GndTemp," "Health", \ + "s" "#" "m" "m" "P" "O" "n" "s" "m" "O" "-", \ + "F" "-" "0" "0" "0" "B" "0" "C" "?" "0" "-", \ true \ }, \ { LOG_BARD_MSG, sizeof(log_BARD), \ diff --git a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp index f25875ad62a11..1e82b840804b6 100644 --- a/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp +++ b/libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp @@ -33,7 +33,6 @@ static AP_Baro barometer; #endif // HAL_EXTERNAL_AHRS_ENABLED static uint32_t timer; -static uint8_t counter; static AP_BoardConfig board_config; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -69,14 +68,9 @@ void loop() return; } - // run accumulate() at 50Hz and update() at 10Hz - if ((AP_HAL::micros() - timer) > 20 * 1000UL) { + // run update() at 10Hz + if ((AP_HAL::micros() - timer) > 100 * 1000UL) { timer = AP_HAL::micros(); - barometer.accumulate(); - if (counter++ < 5) { - return; - } - counter = 0; barometer.update(); //calculate time taken for barometer readings to update diff --git a/libraries/AP_Baro/tests/test_baro_atmosphere.cpp b/libraries/AP_Baro/tests/test_baro_atmosphere.cpp new file mode 100644 index 0000000000000..132d27372e0e5 --- /dev/null +++ b/libraries/AP_Baro/tests/test_baro_atmosphere.cpp @@ -0,0 +1,130 @@ +/* + test atmospheric model + to build, use: + ./waf configure --board sitl --debug + ./waf --target tests/test_baro_atmosphere + */ +#include + +#include + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +TEST(AP_Baro, get_air_density_for_alt_amsl) +{ + float accuracy = 1E-6; + + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(-4000), 1.7697266, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(6000), 0.66011156, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(17500), 131.5688E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(25000), 40.08393E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(40000), 3.99567824728293E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(49000), 1.16276961471707E-3, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(65000), 163.210100967015E-6, accuracy); + EXPECT_NEAR(AP_Baro::get_air_density_for_alt_amsl(78000), 25.2385188936996E-6, accuracy); +} + +TEST(AP_Baro, get_altitude_from_pressure) +{ + AP_Baro baro; + float accuracy = 1.5E-1; + + EXPECT_NEAR(baro.get_altitude_from_pressure(159598.2), -4000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(47217.6), 6000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(8182.3), 17500, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(2549.2), 25000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(287.1441), 40000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(90.3365), 49000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(10.9297), 65000, accuracy); + EXPECT_NEAR(baro.get_altitude_from_pressure(1.4674), 78000, accuracy); +} + +TEST(AP_Baro, get_temperature_from_altitude) +{ + AP_Baro baro; + + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(-4000), 314.166370821781); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(6000), 249.186776458540); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(17500), 216.650000000000); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(25000), 221.552064726284); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(40000), 250.349646102421); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(49000), 270.650000000000); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(65000), 233.292172386848); + EXPECT_FLOAT_EQ(baro.get_temperature_from_altitude(78000), 202.540977853740); +} + +TEST(AP_Baro, geopotential_alt_to_geometric) +{ + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(-4002.51858796625), -4000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(5994.34208330151), 6000.0); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(17451.9552525734), 17500); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(24902.0647262842), 25000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(39749.8736080075), 40000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(48625.1814380981), 49000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(64342.0812904114), 65000); + EXPECT_FLOAT_EQ(AP_Baro::geopotential_alt_to_geometric(77054.5110731299), 78000); +} + +TEST(AP_Baro, geometric_alt_to_geopotential) +{ + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(-4000), -4002.51858796625); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(6000), 5994.34208330151); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(17500), 17451.9552525734); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(25000), 24902.0647262842); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(40000), 39749.8736080075); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(49000), 48625.1814380981); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(65000), 64342.0812904114); + EXPECT_FLOAT_EQ(AP_Baro::geometric_alt_to_geopotential(78000), 77054.5110731299); +} + +TEST(AP_Baro, get_pressure_temperature_for_alt_amsl) +{ + float accuracy = 1E-6; + + // layer 0 -4000 m + float pressure, temperature_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(-4000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 159598.164433755); // Matlab + EXPECT_FLOAT_EQ(pressure, 159598.09375); + EXPECT_FLOAT_EQ(temperature_K, 314.166370821781); + + // layer 0: 6000 m + AP_Baro::get_pressure_temperature_for_alt_amsl(6000, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 47217.6489854302); + EXPECT_FLOAT_EQ(temperature_K, 249.186776458540); + + // layer 1: 17500 m + AP_Baro::get_pressure_temperature_for_alt_amsl(17500, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 8182.27857345022); + EXPECT_FLOAT_EQ(temperature_K, 216.650000000000); + + // layer 2: 25000m + AP_Baro::get_pressure_temperature_for_alt_amsl(25000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 2549.22361148236); // Matlab + EXPECT_FLOAT_EQ(pressure, 2549.2251); + EXPECT_FLOAT_EQ(temperature_K, 221.552064726284); + + // layer 3: 40000m + AP_Baro::get_pressure_temperature_for_alt_amsl(40000, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 287.144059695555); + EXPECT_FLOAT_EQ(temperature_K, 250.349646102421); + + // layer 4: 49000m + AP_Baro::get_pressure_temperature_for_alt_amsl(49000, pressure, temperature_K); + EXPECT_FLOAT_EQ(pressure, 90.3365441635632); + EXPECT_FLOAT_EQ(temperature_K, 270.650000000000); + + // layer 5: 65000m + AP_Baro::get_pressure_temperature_for_alt_amsl(65000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 10.9297197424037); // Matlab + EXPECT_FLOAT_EQ(pressure, 10.929715); + EXPECT_FLOAT_EQ(temperature_K, 233.292172386848); + + // layer 6: 78000m + AP_Baro::get_pressure_temperature_for_alt_amsl(78000, pressure, temperature_K); + // EXPECT_FLOAT_EQ(pressure, 1.46736727632119); // matlab + EXPECT_NEAR(pressure, 1.4673687, accuracy); + EXPECT_FLOAT_EQ(temperature_K, 202.540977853740); +} + +AP_GTEST_MAIN() diff --git a/libraries/AP_Baro/tests/wscript b/libraries/AP_Baro/tests/wscript new file mode 100644 index 0000000000000..cd3e5e3ce7c9d --- /dev/null +++ b/libraries/AP_Baro/tests/wscript @@ -0,0 +1,7 @@ +#!/usr/bin/env python +# encoding: utf-8 + +def build(bld): + bld.ap_find_tests( + use='ap', + ) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index d929b8182a06d..15f44291aa67b 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -66,6 +66,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: _ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: _ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[0], "_", 41, AP_BattMonitor, backend_var_info[0]), #if AP_BATT_MONITOR_MAX_INSTANCES > 1 @@ -87,6 +89,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 2_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 2_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[1], "2_", 42, AP_BattMonitor, backend_var_info[1]), #endif @@ -109,6 +113,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 3_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 3_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[2], "3_", 43, AP_BattMonitor, backend_var_info[2]), #endif @@ -131,6 +137,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 4_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 4_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[3], "4_", 44, AP_BattMonitor, backend_var_info[3]), #endif @@ -153,6 +161,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 5_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 5_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[4], "5_", 45, AP_BattMonitor, backend_var_info[4]), #endif @@ -175,6 +185,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 6_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 6_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[5], "6_", 46, AP_BattMonitor, backend_var_info[5]), #endif @@ -197,6 +209,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 7_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 7_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[6], "7_", 47, AP_BattMonitor, backend_var_info[6]), #endif @@ -219,6 +233,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 8_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 8_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[7], "8_", 48, AP_BattMonitor, backend_var_info[7]), #endif @@ -241,6 +257,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: 9_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: 9_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[8], "9_", 49, AP_BattMonitor, backend_var_info[8]), #endif @@ -263,6 +281,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: A_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: A_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[9], "A_", 50, AP_BattMonitor, backend_var_info[9]), #endif @@ -285,6 +305,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: B_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: B_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[10], "B_", 51, AP_BattMonitor, backend_var_info[10]), #endif @@ -307,6 +329,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: C_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: C_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[11], "C_", 52, AP_BattMonitor, backend_var_info[11]), #endif @@ -329,6 +353,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: D_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: D_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[12], "D_", 53, AP_BattMonitor, backend_var_info[12]), #endif @@ -351,6 +377,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: E_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: E_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[13], "E_", 54, AP_BattMonitor, backend_var_info[13]), #endif @@ -373,6 +401,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: F_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: F_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[14], "F_", 55, AP_BattMonitor, backend_var_info[14]), #endif @@ -395,6 +425,8 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Path: AP_BattMonitor_Synthetic_Current.cpp // @Group: G_ // @Path: AP_BattMonitor_INA2xx.cpp + // @Group: G_ + // @Path: AP_BattMonitor_ESC.cpp AP_SUBGROUPVARPTR(drivers[15], "G_", 56, AP_BattMonitor, backend_var_info[15]), #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 3c7d35fd9e5b9..0af65b951d0a2 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = { // @User: Advanced AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0), - // Param indexes must be between 30 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + // Param indexes must be between 30 and 35 to avoid conflict with other battery monitor param tables loaded by pointer AP_GROUPEND }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp index c633217f531ae..a1c309a6e60ef 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_ESC.cpp @@ -20,6 +20,32 @@ #include "AP_BattMonitor_ESC.h" +const AP_Param::GroupInfo AP_BattMonitor_ESC::var_info[] = { + + // Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + + // @Param: ESC_MASK + // @DisplayName: ESC mask + // @Description: If 0 all connected ESCs will be used. If non-zero, only those selected in will be used. + // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 + // @User: Standard + AP_GROUPINFO("ESC_MASK", 36, AP_BattMonitor_ESC, _mask, 0), + + // Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer + + AP_GROUPEND +}; + +// constructor. This incorporates initialisation as well. +AP_BattMonitor_ESC::AP_BattMonitor_ESC(AP_BattMonitor &mon, + AP_BattMonitor::BattMonitor_State &mon_state, + AP_BattMonitor_Params ¶ms): + AP_BattMonitor_Backend(mon, mon_state, params) +{ + AP_Param::setup_object_defaults(this, var_info); + _state.var_info = var_info; +}; + void AP_BattMonitor_ESC::init(void) { } @@ -34,9 +60,15 @@ void AP_BattMonitor_ESC::read(void) float current_sum = 0; float temperature_sum = 0; uint32_t highest_ms = 0; - _state.consumed_mah = delta_mah; + _state.consumed_mah = delta_mah; + const bool all_enabled = _mask == 0; for (uint8_t i=0; iget_batt_info(volts, current_amps, temp_C, remaining_pct)) { + if (torqeedo->get_batt_info(_state.instance, volts, current_amps, temp_C, remaining_pct)) { have_info = true; _state.voltage = volts; _state.current_amps = current_amps; @@ -56,9 +57,10 @@ void AP_BattMonitor_Torqeedo::read(void) } // read battery pack capacity + // assumes battery monitor instance matches torqeedo instance if (!have_capacity) { uint16_t batt_capacity_ah; - if (torqeedo->get_batt_capacity_Ah(batt_capacity_ah)) { + if (torqeedo->get_batt_capacity_Ah(_state.instance, batt_capacity_ah)) { have_capacity = true; if (batt_capacity_ah * 1000 != _params._pack_capacity) { _params._pack_capacity.set_and_notify(batt_capacity_ah * 1000); diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index 1457d86b6235d..e60b8e04b1479 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -225,7 +225,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1), #endif -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED // @Group: RADIO // @Path: ../AP_Radio/AP_Radio.cpp AP_SUBGROUPINFO(_radio, "RADIO", 11, AP_BoardConfig, AP_Radio), diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index 938180a238bb9..3f6401d6249f9 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -5,8 +5,9 @@ #include #include #include +#include -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED #include #endif @@ -292,7 +293,7 @@ class AP_BoardConfig { } heater; #endif -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED // direct attached radio AP_Radio _radio; #endif diff --git a/libraries/AP_CANManager/AP_CANSensor.h b/libraries/AP_CANManager/AP_CANSensor.h index 7ba0021bb1346..7afd1bbea0fa5 100644 --- a/libraries/AP_CANManager/AP_CANSensor.h +++ b/libraries/AP_CANManager/AP_CANSensor.h @@ -36,6 +36,9 @@ class CANSensor : public AP_CANDriver { void init(uint8_t driver_index, bool enable_filters) override; bool add_interface(AP_HAL::CANIface* can_iface) override; + // Return true if this sensor has been successfully registered to a driver and initialized. + bool initialized() const { return _initialized; } + // handler for incoming frames virtual void handle_frame(AP_HAL::CANFrame &frame) = 0; diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 50f134fb5b363..f414b6a9a1481 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -294,6 +294,19 @@ Vector3d Location::get_distance_NED_double(const Location &loc2) const (alt - loc2.alt) * 0.01); } +// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2 considering alt frame, if altitude cannot be resolved down distance is 0 +Vector3f Location::get_distance_NED_alt_frame(const Location &loc2) const +{ + int32_t alt1, alt2 = 0; + if (!get_alt_cm(AltFrame::ABSOLUTE, alt1) || !loc2.get_alt_cm(AltFrame::ABSOLUTE, alt2)) { + // one or both of the altitudes are invalid, don't do alt distance calc + alt1 = 0, alt2 = 0; + } + return Vector3f((loc2.lat - lat) * LOCATION_SCALING_FACTOR, + diff_longitude(loc2.lng,lng) * LOCATION_SCALING_FACTOR * longitude_scale((loc2.lat+lat)/2), + (alt1 - alt2) * 0.01); +} + Vector2d Location::get_distance_NE_double(const Location &loc2) const { return Vector2d((loc2.lat - lat) * double(LOCATION_SCALING_FACTOR), diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 344187bf64a63..e84be52611105 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -73,6 +73,9 @@ class Location Vector3f get_distance_NED(const Location &loc2) const; Vector3d get_distance_NED_double(const Location &loc2) const; + // return the distance in meters in North/East/Down plane as a N/E/D vector to loc2 considering alt frame, if altitude cannot be resolved down distance is 0 + Vector3f get_distance_NED_alt_frame(const Location &loc2) const; + // return the distance in meters in North/East plane as a N/E vector to loc2 Vector2f get_distance_NE(const Location &loc2) const; Vector2d get_distance_NE_double(const Location &loc2) const; 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.cpp b/libraries/AP_DAL/AP_DAL.cpp index 986fe66bcf025..6c8824a5a4522 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -65,7 +65,7 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) _RFRN.lat = _home.lat; _RFRN.lng = _home.lng; _RFRN.alt = _home.alt; - _RFRN.EAS2TAS = AP::baro().get_EAS2TAS(); + _RFRN.EAS2TAS = ahrs.get_EAS2TAS(); _RFRN.vehicle_class = (uint8_t)ahrs.get_vehicle_class(); _RFRN.fly_forward = ahrs.get_fly_forward(); _RFRN.takeoff_expected = ahrs.get_takeoff_expected(); diff --git a/libraries/AP_DAL/AP_DAL_InertialSensor.cpp b/libraries/AP_DAL/AP_DAL_InertialSensor.cpp index e8332cb7ad41d..136e905f52af6 100644 --- a/libraries/AP_DAL/AP_DAL_InertialSensor.cpp +++ b/libraries/AP_DAL/AP_DAL_InertialSensor.cpp @@ -54,9 +54,9 @@ void AP_DAL_InertialSensor::start_frame() void AP_DAL_InertialSensor::update_filtered(uint8_t i) { if (!is_positive(alpha)) { - // we use a constant 20Hz for EKF filtered accel/gyro, making the EKF + // we use a constant 10Hz for EKF filtered accel/gyro, making the EKF // independent of the INS filter settings - const float cutoff_hz = 20.0; + const float cutoff_hz = 10.0; alpha = calc_lowpass_alpha_dt(get_loop_delta_t(), cutoff_hz); } if (is_positive(_RISI[i].delta_angle_dt)) { 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_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index b72899bf72cae..67c629b241616 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -61,6 +61,8 @@ #include +#include + extern const AP_HAL::HAL& hal; // setup default pool size @@ -396,6 +398,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) #if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED AP_TemperatureSensor_DroneCAN::subscribe_msgs(this); #endif +#if AP_RPM_DRONECAN_ENABLED + AP_RPM_DroneCAN::subscribe_msgs(this); +#endif act_out_array.set_timeout_ms(5); act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH); diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript index 3e81beeee182a..6de16dbf02cdd 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/wscript @@ -11,8 +11,6 @@ def build(bld): dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', ap_libraries=bld.ap_common_vehicle_libraries() + [ 'AP_OSD', - 'AP_RCMapper', - 'AP_Arming' ], ) bld.ap_program( diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index a82a014dedd64..9a3e34f84251e 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -318,8 +318,11 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) const uint32_t now_us = AP_HAL::micros(); // loop through groups of 4 ESCs - const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS - 1); - const uint8_t num_idx = ESC_TELEM_MAX_ESCS / 4; + const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1); + + // ensure we send out partially-full groups: + const uint8_t num_idx = (ESC_TELEM_MAX_ESCS + 3) / 4; + for (uint8_t idx = 0; idx < num_idx; idx++) { const uint8_t i = (next_idx + idx) % num_idx; @@ -465,6 +468,15 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem telemdata.usage_s = new_data.usage_s; } +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STATUS) { + telemdata.edt2_status = merge_edt2_status(telemdata.edt2_status, new_data.edt2_status); + } + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STRESS) { + telemdata.edt2_stress = merge_edt2_stress(telemdata.edt2_stress, new_data.edt2_stress); + } +#endif + telemdata.count++; telemdata.types |= data_mask; telemdata.last_update_ms = AP_HAL::millis(); @@ -496,6 +508,63 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, cons #endif } +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + +// The following is based on https://github.com/bird-sanctuary/extended-dshot-telemetry. +// For the following part we explain the bits of Extended DShot Telemetry v2 status telemetry: +// - bits 0-3: the "stress level" +// - bit 5: the "error" bit (e.g. the stall event in Bluejay) +// - bit 6: the "warning" bit (e.g. the desync event in Bluejay) +// - bit 7: the "alert" bit (e.g. the demag event in Bluejay) + +// Since logger can read out telemetry values less frequently than they are updated, +// it makes sense to aggregate these status bits, and to collect the maximum observed stress level. +// To reduce the logging rate of the EDT2 messages, we will try to log them only once a new frame comes. +// To track this, we are going to (ab)use bit 15 of the field: 1 means there is something to write. + +// EDTv2 also features separate "stress" messages. +// These come more frequently, and are scaled differently (the allowed range is from 0 to 255), +// so we have to log them separately. + +constexpr uint16_t EDT2_TELEM_UPDATED = 0x8000U; +constexpr uint16_t EDT2_STRESS_0F_MASK = 0xfU; +constexpr uint16_t EDT2_STRESS_FF_MASK = 0xffU; +constexpr uint16_t EDT2_ERROR_MASK = 0x20U; +constexpr uint16_t EDT2_WARNING_MASK = 0x40U; +constexpr uint16_t EDT2_ALERT_MASK = 0x80U; +constexpr uint16_t EDT2_ALL_BITS = EDT2_ERROR_MASK | EDT2_WARNING_MASK | EDT2_ALERT_MASK; + +#define EDT2_HAS_NEW_DATA(status) bool((status) & EDT2_TELEM_UPDATED) +#define EDT2_STRESS_FROM_STATUS(status) uint8_t((status) & EDT2_STRESS_0F_MASK) +#define EDT2_ERROR_BIT_FROM_STATUS(status) bool((status) & EDT2_ERROR_MASK) +#define EDT2_WARNING_BIT_FROM_STATUS(status) bool((status) & EDT2_WARNING_MASK) +#define EDT2_ALERT_BIT_FROM_STATUS(status) bool((status) & EDT2_ALERT_MASK) +#define EDT2_STRESS_FROM_STRESS(stress) uint8_t((stress) & EDT2_STRESS_FF_MASK) + +uint16_t AP_ESC_Telem::merge_edt2_status(uint16_t old_status, uint16_t new_status) +{ + if (EDT2_HAS_NEW_DATA(old_status)) { + new_status = uint16_t( + (old_status & ~EDT2_STRESS_0F_MASK) | // old status except for the stress is preserved + (new_status & EDT2_ALL_BITS) | // all new status bits are included + MAX(old_status & EDT2_STRESS_0F_MASK, new_status & EDT2_STRESS_0F_MASK) // the stress is maxed out + ); + } + return EDT2_TELEM_UPDATED | new_status; +} + +uint16_t AP_ESC_Telem::merge_edt2_stress(uint16_t old_stress, uint16_t new_stress) +{ + if (EDT2_HAS_NEW_DATA(old_stress)) { + new_stress = uint16_t( + MAX(old_stress & EDT2_STRESS_FF_MASK, new_stress & EDT2_STRESS_FF_MASK) // the stress is maxed out + ); + } + return EDT2_TELEM_UPDATED | new_stress; +} + +#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + void AP_ESC_Telem::update() { #if HAL_LOGGING_ENABLED @@ -504,7 +573,7 @@ void AP_ESC_Telem::update() for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { const volatile AP_ESC_Telem_Backend::RpmData &rpmdata = _rpm_data[i]; - const volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[i]; + volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[i]; // Push received telemetry data into the logging system if (logger && logger->logging_enabled()) { if (telemdata.last_update_ms != _last_telem_log_ms[i] @@ -541,6 +610,51 @@ void AP_ESC_Telem::update() _last_telem_log_ms[i] = telemdata.last_update_ms; _last_rpm_log_us[i] = rpmdata.last_update_us; } + +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + // Write an EDTv2 message, if there is any update + uint16_t edt2_status = telemdata.edt2_status; + uint16_t edt2_stress = telemdata.edt2_stress; + if (EDT2_HAS_NEW_DATA(edt2_status | edt2_stress)) { + // Could probably be faster/smaller with bitmasking, but not sure + uint8_t status = 0; + if (EDT2_HAS_NEW_DATA(edt2_stress)) { + status |= uint8_t(log_Edt2_Status::HAS_STRESS_DATA); + } + if (EDT2_HAS_NEW_DATA(edt2_status)) { + status |= uint8_t(log_Edt2_Status::HAS_STATUS_DATA); + } + if (EDT2_ALERT_BIT_FROM_STATUS(edt2_status)) { + status |= uint8_t(log_Edt2_Status::ALERT_BIT); + } + if (EDT2_WARNING_BIT_FROM_STATUS(edt2_status)) { + status |= uint8_t(log_Edt2_Status::WARNING_BIT); + } + if (EDT2_ERROR_BIT_FROM_STATUS(edt2_status)) { + status |= uint8_t(log_Edt2_Status::ERROR_BIT); + } + // An EDT2 status message is: + // id: starts from 0 + // stress: the current stress which comes from edt2_stress + // max_stress: the maximum stress which comes from edt2_status + // status: the status bits which come from both + const struct log_Edt2 pkt_edt2{ + LOG_PACKET_HEADER_INIT(uint8_t(LOG_EDT2_MSG)), + time_us : now_us64, + instance : i, + stress : EDT2_STRESS_FROM_STRESS(edt2_stress), + max_stress : EDT2_STRESS_FROM_STATUS(edt2_status), + status : status, + }; + if (AP::logger().WriteBlock_first_succeed(&pkt_edt2, sizeof(pkt_edt2))) { + // Only clean the telem_updated bits if the write succeeded. + // This is important because, if rate limiting is enabled, + // the log-on-change behavior may lose a lot of entries + telemdata.edt2_status &= ~EDT2_TELEM_UPDATED; + telemdata.edt2_stress &= ~EDT2_TELEM_UPDATED; + } + } +#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED } } #endif // HAL_LOGGING_ENABLED @@ -605,4 +719,4 @@ AP_ESC_Telem &esc_telem() }; -#endif +#endif // HAL_WITH_ESC_TELEM diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index ae40ede597079..4c5d0719915b8 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -118,6 +118,12 @@ class AP_ESC_Telem { static bool rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us); static bool was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance); +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + // helpers that aggregate data in EDTv2 messages + static uint16_t merge_edt2_status(uint16_t old_status, uint16_t new_status); + static uint16_t merge_edt2_stress(uint16_t old_stress, uint16_t new_stress); +#endif + // rpm data volatile AP_ESC_Telem_Backend::RpmData _rpm_data[ESC_TELEM_MAX_ESCS]; // telemetry data diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index b6d6725a55fa1..e46eb48ceb6b0 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -19,6 +19,10 @@ class AP_ESC_Telem_Backend { uint32_t last_update_ms; // last update time in milliseconds, determines whether active uint16_t types; // telemetry types present uint16_t count; // number of times updated +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + uint16_t edt2_status; // status reported by Extended DShot Telemetry v2 + uint16_t edt2_stress; // stress reported in dedicated messages by Extended DShot Telemetry v2 +#endif // return true if the data is stale bool stale(uint32_t now_ms=0) const volatile; @@ -42,6 +46,10 @@ class AP_ESC_Telem_Backend { USAGE = 1 << 5, TEMPERATURE_EXTERNAL = 1 << 6, MOTOR_TEMPERATURE_EXTERNAL = 1 << 7, +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + EDT2_STATUS = 1 << 8, + EDT2_STRESS = 1 << 9, +#endif }; diff --git a/libraries/AP_ESC_Telem/LogStructure.h b/libraries/AP_ESC_Telem/LogStructure.h index a3c0dc791cd3d..c50ac47b95e97 100644 --- a/libraries/AP_ESC_Telem/LogStructure.h +++ b/libraries/AP_ESC_Telem/LogStructure.h @@ -3,7 +3,8 @@ #include #define LOG_IDS_FROM_ESC_TELEM \ - LOG_ESC_MSG + LOG_ESC_MSG, \ + LOG_EDT2_MSG // @LoggerMessage: ESC // @Description: Feedback received from ESCs @@ -31,6 +32,35 @@ struct PACKED log_Esc { float error_rate; }; -#define LOG_STRUCTURE_FROM_ESC_TELEM \ +enum class log_Edt2_Status : uint8_t { + HAS_STRESS_DATA = 1U<<0, // true if the message contains up-to-date stress data + HAS_STATUS_DATA = 1U<<1, // true if the message contains up-to-date status data + ALERT_BIT = 1U<<2, // true if the last status had the "alert" bit (e.g. demag) + WARNING_BIT = 1U<<3, // true if the last status had the "warning" bit (e.g. desync) + ERROR_BIT = 1U<<4, // true if the last status had the "error" bit (e.g. stall) +}; + + +// @LoggerMessage: EDT2 +// @Description: Status received from ESCs via Extended DShot telemetry v2 +// @Field: TimeUS: microseconds since system startup +// @Field: Instance: ESC instance number +// @Field: Stress: current stress level (commutation effort), scaled to [0..255] +// @Field: MaxStress: maximum stress level (commutation effort) since arming, scaled to [0..15] +// @Field: Status: status bits +// @FieldBitmaskEnum: Status: log_Edt2_Status +struct PACKED log_Edt2 { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t instance; + uint8_t stress; + uint8_t max_stress; + uint8_t status; +}; + +#define LOG_STRUCTURE_FROM_ESC_TELEM \ { LOG_ESC_MSG, sizeof(log_Esc), \ - "ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true }, + "ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true }, \ + { LOG_EDT2_MSG, sizeof(log_Edt2), \ + "EDT2", "QBBBB", "TimeUS,Instance,Stress,MaxStress,Status", "s#---", "F----" , true }, + diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index 315cc17b22765..7900bab8256e9 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -29,6 +29,7 @@ #include #include +#include #include extern const AP_HAL::HAL &hal; @@ -238,6 +239,27 @@ bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) if (!backend->pre_arm_check(failure_msg, failure_msg_len)) { return false; } + // Verify the user has configured the GPS to accept EAHRS data. + if (has_sensor(AvailableSensor::GPS)) { + const auto eahrs_gps_sensors = backend->num_gps_sensors(); + + const auto &gps = AP::gps(); + uint8_t n_configured_eahrs_gps = 0; + for (uint8_t i = 0; i < GPS_MAX_INSTANCES; ++i) { + const auto gps_type = gps.get_type(i); + if (gps_type == AP_GPS::GPS_TYPE_EXTERNAL_AHRS) { + n_configured_eahrs_gps++; + } + } + + // Once AP supports at least 3 GPS's, change to == and remove the second condition. + // At that point, enforce that all GPS's in EAHRS can report to AP_GPS. + if (n_configured_eahrs_gps < 1 && eahrs_gps_sensors >= 1) { + hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Incorrect number of GPS sensors configured for EAHRS"); + return false; + } + } + if (!state.have_origin) { hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: No origin"); return false; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h index bee7d5c28e0cc..9de2c9526e931 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h @@ -181,6 +181,12 @@ class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { uint16_t buffer_ofs; uint8_t buffer[256]; // max for normal message set is 167+8 +protected: + + uint8_t num_gps_sensors(void) const override { + return 1; + } + private: AP_HAL::UARTDriver *uart; int8_t port_num; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h index e6b2b9e6bdcb1..7d5c199eb1365 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h @@ -49,6 +49,12 @@ class AP_ExternalAHRS_MicroStrain5: public AP_ExternalAHRS_backend, public AP_Mi build_packet(); }; +protected: + + uint8_t num_gps_sensors(void) const override { + return 1; + } + private: uint32_t baudrate; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp index 901fff1c84cf5..4203625a812f6 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp @@ -18,6 +18,7 @@ param set AHRS_EKF_TYPE 11 param set EAHRS_TYPE 7 param set GPS1_TYPE 21 + param set GPS2_TYPE 21 param set SERIAL3_BAUD 115 param set SERIAL3_PROTOCOL 36 UDEV rules for repeatable USB connection: @@ -269,28 +270,24 @@ bool AP_ExternalAHRS_MicroStrain7::initialised(void) const 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"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "not initialised"); return false; } if (!times_healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "data is stale"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "data is stale"); return false; } if (!filter_healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "filter is unhealthy"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "filter is unhealthy"); return false; } if (!healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, get_name(), "unhealthy"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "unhealthy"); return false; } 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, get_name(), "filter not healthy"); + hal.util->snprintf(failure_msg, failure_msg_len, LOG_FMT, get_name(), "missing 3D GPS fix on either GPS"); return false; } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h index 5cff5af56a6dc..f278289d15fb4 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h @@ -50,6 +50,13 @@ class AP_ExternalAHRS_MicroStrain7: public AP_ExternalAHRS_backend, public AP_Mi build_packet(); }; +protected: + + uint8_t num_gps_sensors(void) const override + { + return AP_MicroStrain::NUM_GNSS_INSTANCES; + } + private: // GQ7 Filter States diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index 3ce1fe7f5e2d5..c0e54c88bf2a4 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -47,6 +47,11 @@ class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend { // Get model/type name const char* get_name() const override; +protected: + + uint8_t num_gps_sensors(void) const override { + return 1; + } private: AP_HAL::UARTDriver *uart; int8_t port_num; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h index ed987a01ced3a..e5a22a87cbe44 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h @@ -48,6 +48,9 @@ class AP_ExternalAHRS_backend { // This can also copy interim state protected by locking. virtual void update() = 0; + // Return the number of GPS sensors sharing data to AP_GPS. + virtual uint8_t num_gps_sensors(void) const = 0; + protected: AP_ExternalAHRS::state_t &state; uint16_t get_rate(void) const; diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index b7642da19cfcf..63f575bb5be2d 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -306,7 +306,9 @@ void AP_Filesystem::unmount(void) } /* - load a file to memory as a single chunk. Use only for small files + Load a file's contents into memory. Returned object must be `delete`d to free + the data. The data is guaranteed to be null-terminated such that it can be + treated as a string. */ FileData *AP_Filesystem::load_file(const char *filename) { diff --git a/libraries/AP_Filesystem/AP_Filesystem.h b/libraries/AP_Filesystem/AP_Filesystem.h index a6ebc358dcdf8..c2bd20e765563 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.h +++ b/libraries/AP_Filesystem/AP_Filesystem.h @@ -132,7 +132,9 @@ class AP_Filesystem { AP_Filesystem_Backend::FormatStatus get_format_status() const; /* - load a full file. Use delete to free the data + Load a file's contents into memory. Returned object must be `delete`d to + free the data. The data is guaranteed to be null-terminated such that it + can be treated as a string. */ FileData *load_file(const char *filename); diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp index 930b4f62682c7..f1aa5d69d9884 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp @@ -239,8 +239,9 @@ bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_s } /* - load a full file. Use delete to free the data - we override this in ROMFS to avoid taking twice the memory + Load a file's contents into memory. Returned object must be `delete`d to free + the data. The data is guaranteed to be null-terminated such that it can be + treated as a string. Overridden in ROMFS to avoid taking twice the memory. */ FileData *AP_Filesystem_ROMFS::load_file(const char *filename) { @@ -248,6 +249,7 @@ FileData *AP_Filesystem_ROMFS::load_file(const char *filename) if (!fd) { return nullptr; } + // AP_ROMFS adds the guaranteed termination so we don't have to. fd->data = AP_ROMFS::find_decompress(filename, fd->length); if (fd->data == nullptr) { delete fd; diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp index 87fe694d9ec61..342eac4dbdc0b 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp @@ -19,7 +19,9 @@ extern const AP_HAL::HAL& hal; /* - load a full file. Use delete to free the data + Load a file's contents into memory. Returned object must be `delete`d to free + the data. The data is guaranteed to be null-terminated such that it can be + treated as a string. */ FileData *AP_Filesystem_Backend::load_file(const char *filename) { @@ -31,7 +33,8 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename) if (fd == nullptr) { return nullptr; } - void *data = malloc(st.st_size); + // add one byte for null termination; ArduPilot's malloc will zero it. + void *data = malloc(st.st_size+1); if (data == nullptr) { delete fd; return nullptr; @@ -49,7 +52,7 @@ FileData *AP_Filesystem_Backend::load_file(const char *filename) return nullptr; } close(d); - fd->length = st.st_size; + fd->length = st.st_size; // length does not include our added termination fd->data = (const uint8_t *)data; return fd; } diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.h b/libraries/AP_Filesystem/AP_Filesystem_backend.h index 187f9c48c3041..8cf0fa655a1cf 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.h +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.h @@ -87,7 +87,9 @@ class AP_Filesystem_Backend { virtual AP_Filesystem_Backend::FormatStatus get_format_status() const { return FormatStatus::NOT_STARTED; } /* - load a full file. Use delete to free the data + Load a file's contents into memory. Returned object must be `delete`d to + free the data. The data is guaranteed to be null-terminated such that it + can be treated as a string. */ virtual FileData *load_file(const char *filename); diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 91b7c0dcd1c65..73829001c8771 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -980,7 +980,7 @@ void AP_GPS::update_instance(uint8_t instance) #if GPS_MOVING_BASELINE -void AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) +bool AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) { for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) { if (drivers[i] && @@ -991,8 +991,10 @@ void AP_GPS::get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float relPosD = state[i].relPosD; accHeading = state[i].accHeading; timestamp = state[i].relposheading_ts; + return true; } } + return false; } bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len) diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 70879831078eb..e21bf66524631 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -197,7 +197,7 @@ class AP_GPS uint16_t time_week; ///< GPS week number Location location; ///< last fix location float ground_speed; ///< ground speed in m/s - float ground_course; ///< ground course in degrees + float ground_course; ///< ground course in degrees, wrapped 0-360 float gps_yaw; ///< GPS derived yaw information, if available (degrees) uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading bool gps_yaw_configured; ///< GPS is configured to provide yaw @@ -594,7 +594,7 @@ class AP_GPS #if GPS_MOVING_BASELINE // methods used by UAVCAN GPS driver and AP_Periph for moving baseline void inject_MBL_data(uint8_t* data, uint16_t length); - void get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading); + bool get_RelPosHeading(uint32_t ×tamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) WARN_IF_UNUSED; bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len); void clear_RTCMV3(); #endif // GPS_MOVING_BASELINE diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 4fbfef5833a2d..4327c9f4d4bbb 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -326,7 +326,7 @@ AP_GPS_GSOF::process_message(void) if ((vflag & 1) == 1) { state.ground_speed = SwapFloat(msg.data, a + 1); - state.ground_course = degrees(SwapFloat(msg.data, a + 5)); + state.ground_course = wrap_360(degrees(SwapFloat(msg.data, a + 5))); fill_3d_velocity(); state.velocity.z = -SwapFloat(msg.data, a + 9); state.have_vertical_velocity = true; diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 5ba862d7ef177..24b6a66d3b5c6 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -163,10 +163,6 @@ #define HAL_NUM_CAN_IFACES 0 #endif -#ifndef HAL_RCINPUT_WITH_AP_RADIO -#define HAL_RCINPUT_WITH_AP_RADIO 0 -#endif - #ifndef HAL_WITH_IO_MCU #define HAL_WITH_IO_MCU 0 #endif @@ -179,6 +175,19 @@ #define HAL_WITH_IO_MCU_DSHOT HAL_WITH_IO_MCU_BIDIR_DSHOT #endif +#ifndef HAL_REQUIRES_BDSHOT_SUPPORT +#define HAL_REQUIRES_BDSHOT_SUPPORT (defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT) +#endif + +// support for Extended DShot Telemetry v2 is enabled only if any kind of such telemetry +// can in principle arrive, either from servo outputs or from IOMCU + +// if not desired, set to 0 - and if IOMCU has bidirectional DShot enabled, recompile it too, +// otherwise the communication to IOMCU breaks! +#ifndef AP_EXTENDED_DSHOT_TELEM_V2_ENABLED +#define AP_EXTENDED_DSHOT_TELEM_V2_ENABLED HAL_REQUIRES_BDSHOT_SUPPORT +#endif + // this is used as a general mechanism to make a 'small' build by // dropping little used features. We use this to allow us to keep // FMUv2 going for as long as possible 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/DataRateLimit.cpp b/libraries/AP_HAL/utility/DataRateLimit.cpp new file mode 100644 index 0000000000000..a61259428b919 --- /dev/null +++ b/libraries/AP_HAL/utility/DataRateLimit.cpp @@ -0,0 +1,25 @@ +#include "DataRateLimit.h" + +#include + +// Return the max number of bytes that can be sent since the last call given byte/s rate limit +uint32_t DataRateLimit::max_bytes(const float bytes_per_sec) +{ + // Time since last call + const uint32_t now_us = AP_HAL::micros(); + const float dt = (now_us - last_us) * 1.0e-6; + last_us = now_us; + + // Maximum number of bytes that could be transferred in that time + float max_bytes = bytes_per_sec * dt; + + // Add on the remainder from the last call, this prevents cumulative rounding errors + max_bytes += remainder; + + // Get integer number of bytes and store the remainder + float max_bytes_int; + remainder = modf(max_bytes, &max_bytes_int); + + // Add 0.5 to make sure the float rounds to the correct int + return uint32_t(max_bytes_int + 0.5); +} diff --git a/libraries/AP_HAL/utility/DataRateLimit.h b/libraries/AP_HAL/utility/DataRateLimit.h new file mode 100644 index 0000000000000..ec8f55e37a305 --- /dev/null +++ b/libraries/AP_HAL/utility/DataRateLimit.h @@ -0,0 +1,26 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +#pragma once + +#include + +// Returns the max number of bytes that can be sent since the last call given byte/s rate limit +class DataRateLimit { +public: + uint32_t max_bytes(const float bytes_per_sec); +private: + uint32_t last_us; + float remainder; +}; diff --git a/libraries/AP_HAL_ChibiOS/RCInput.cpp b/libraries/AP_HAL_ChibiOS/RCInput.cpp index cd44c7b3644d6..2f4e460b377e6 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCInput.cpp @@ -84,15 +84,6 @@ bool RCInput::new_input() _last_read = _rcin_timestamp_last_signal; } -#if HAL_RCINPUT_WITH_AP_RADIO - if (!_radio_init) { - _radio_init = true; - radio = AP_Radio::get_singleton(); - if (radio) { - radio->init(); - } - } -#endif return valid; } @@ -114,12 +105,6 @@ uint16_t RCInput::read(uint8_t channel) WITH_SEMAPHORE(rcin_mutex); v = _rc_values[channel]; } -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio && channel == 0) { - // hook to allow for update of radio on main thread, for mavlink sends - radio->update(); - } -#endif return v; } @@ -136,12 +121,6 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len) WITH_SEMAPHORE(rcin_mutex); memcpy(periods, _rc_values, len*sizeof(periods[0])); } -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio) { - // hook to allow for update of radio on main thread, for mavlink sends - radio->update(); - } -#endif return len; } @@ -186,7 +165,7 @@ void RCInput::_timer_tick(void) if (!have_iocmu_rc) { _rcin_last_iomcu_ms = 0; } -#elif AP_RCPROTOCOL_ENABLED || HAL_RCINPUT_WITH_AP_RADIO +#elif AP_RCPROTOCOL_ENABLED const bool have_iocmu_rc = false; #endif @@ -206,22 +185,6 @@ void RCInput::_timer_tick(void) } #endif // AP_RCPROTOCOL_ENABLED -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio && radio->last_recv_us() != last_radio_us && !have_iocmu_rc) { - last_radio_us = radio->last_recv_us(); - WITH_SEMAPHORE(rcin_mutex); - _rcin_timestamp_last_signal = last_radio_us; - _num_channels = radio->num_channels(); - _num_channels = MIN(_num_channels, RC_INPUT_MAX_CHANNELS); - for (uint8_t i=0; i<_num_channels; i++) { - _rc_values[i] = radio->read(i); - } -#ifndef HAL_NO_UARTDRIVER - source = RCSource::APRADIO; -#endif - } -#endif - #if HAL_WITH_IO_MCU { WITH_SEMAPHORE(rcin_mutex); @@ -269,11 +232,6 @@ bool RCInput::rc_bind(int dsmMode) AP::RC().start_bind(); #endif -#if HAL_RCINPUT_WITH_AP_RADIO - if (radio) { - radio->start_recv_bind(); - } -#endif return true; } #endif //#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS diff --git a/libraries/AP_HAL_ChibiOS/RCInput.h b/libraries/AP_HAL_ChibiOS/RCInput.h index 0b3ec8ea5a575..5d03d563003e7 100644 --- a/libraries/AP_HAL_ChibiOS/RCInput.h +++ b/libraries/AP_HAL_ChibiOS/RCInput.h @@ -19,10 +19,6 @@ #include "AP_HAL_ChibiOS.h" #include "Semaphores.h" -#if HAL_RCINPUT_WITH_AP_RADIO -#include -#endif - #include #if HAL_USE_ICU == TRUE @@ -80,17 +76,10 @@ class ChibiOS::RCInput : public AP_HAL::RCInput { IOMCU = 1, RCPROT_PULSES = 2, RCPROT_BYTES = 3, - APRADIO = 4, } last_source; bool pulse_input_enabled; -#if HAL_RCINPUT_WITH_AP_RADIO - bool _radio_init; - AP_Radio *radio; - uint32_t last_radio_us; -#endif - #if HAL_USE_ICU == TRUE ChibiOS::SoftSigReader sig_reader; #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index cb1c04e29d574..7b2e88089f851 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -755,12 +755,12 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c uint16_t value = (encodederpm & 0x000001ffU); // 9bits #if HAL_WITH_ESC_TELEM uint8_t normalized_chan = chan; -#endif #if HAL_WITH_IO_MCU if (iomcu_enabled) { normalized_chan = chan + chan_offset; } #endif +#endif // HAL_WITH_ESC_TELEM: one can possibly imagine a FC with IOMCU but with ESC_TELEM compiled out... if (!(value & 0x100U) && (_dshot_esc_type == DSHOT_ESC_BLHELI_EDT || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S)) { switch (expo) { @@ -796,10 +796,28 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c break; case 0b100: // Debug 1 case 0b101: // Debug 2 - case 0b110: // Stress level - case 0b111: // Status return false; break; + case 0b110: { // Stress level + #if HAL_WITH_ESC_TELEM && AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + TelemetryData t { + .edt2_stress = value + }; + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::EDT2_STRESS); + #endif + return false; + } + break; + case 0b111: { // Status + #if HAL_WITH_ESC_TELEM && AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + TelemetryData t { + .edt2_status = value + }; + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::EDT2_STATUS); + #endif + return false; + } + break; default: // eRPM break; } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat index f107450d24c8c..7c7f6d4fdd762 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat @@ -33,6 +33,10 @@ SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 USART6 OTG2 # order of UARTs (and USB) with IO MCU # SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 +# debug console +STDOUT_SERIAL SD3 +STDOUT_BAUDRATE 57600 + # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN @@ -81,7 +85,8 @@ PD9 USART3_RX USART3 # USART6 is for IOMCU PC6 USART6_TX USART6 -PC7 USART6_RX USART6 +# used for RC SBUS +#PC7 USART6_RX USART6 # Uncomment this line for carriers boards with an IO MCU # IOMCU_UART USART6 @@ -280,7 +285,7 @@ PG0 HW_VER_REV_DRIVE OUTPUT LOW PF9 TIM14_CH1 TIM14 GPIO(77) ALARM # RC input -PI5 TIM8_CH1 TIM8 RCININT PULLDOWN LOW +PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW # barometers BARO BMP388 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat index 6a1236d5b1db6..6fc66e5b4c549 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat @@ -154,10 +154,10 @@ PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR //S1 PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) //S2 PA0 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR //S3 PA1 TIM2_CH2 TIM2 PWM(4) GPIO(53) //S4 -PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR //S5 -PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55) //S6 -PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR //S7 -PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) //S8 +PA2 TIM5_CH3 TIM5 PWM(8) GPIO(54) BIDIR //S8 +PA3 TIM5_CH4 TIM5 PWM(7) GPIO(55) //S7 +PD12 TIM4_CH1 TIM4 PWM(6) GPIO(56) BIDIR //S6 +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(57) //S5 PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) BIDIR //S9 PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) //S10 @@ -218,6 +218,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin # enable logging to dataflash define HAL_LOGGING_DATAFLASH_ENABLED 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX 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..2059843c09e12 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BlitzH743Pro/defaults.parm @@ -0,0 +1,6 @@ +# setup for LEDs on chan9 +SERVO13_FUNCTION 120 +NTF_LED_TYPES 257 + +#enable CAN port +CAN_P1_DRIVER 1 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 b16621fed42c3..cab64cc1697eb 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat index 7437418d97a72..92d316f80ab61 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat index 003ee1508e9e0..ea87ad64b0aef 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat @@ -60,3 +60,4 @@ define HAL_PICCOLO_CAN_ENABLE 0 define AP_RELAY_ENABLED 1 define AP_SERVORELAYEVENTS_ENABLED 1 +define AP_SCHEDULER_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat index 5f7421a78f114..50f6407581421 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat @@ -107,11 +107,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/JHEM_JHEF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat index 19fa51f746848..dd81acb853ff6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEM_JHEF405/hwdef-bl.dat @@ -21,7 +21,11 @@ FLASH_RESERVE_START_KB 0 FLASH_BOOTLOADER_LOAD_KB 48 # order of UARTs (and USB) -SERIAL_ORDER OTG1 +SERIAL_ORDER OTG1 USART6 + +# adding USART6 to be active in bl +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 # PA10 IO-debug-console PA11 OTG_FS_DM OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat index 98d7f7c038865..5e3a7b1bdbd70 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat @@ -9,4 +9,4 @@ SPIDEV bmi270 SPI4 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat index d871100d15b3d..2a40cc91f5912 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat @@ -65,6 +65,6 @@ DMA_NOSHARE *UP SPI1* # Motor order implies Betaflight/X for standard ESCs define HAL_FRAME_TYPE_DEFAULT 12 define HAL_LOGGING_DATAFLASH_ENABLED 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX define AP_SCRIPTING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat index 942924ad471a7..193e3ca2da19f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat @@ -101,17 +101,18 @@ define HAL_GPIO_B_LED_PIN 90 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 @@ -180,7 +181,7 @@ IMU BMI270 SPI:bmi270 ROTATION_PITCH_180 IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180 IMU Invensensev3 SPI:icm42688_2 ROTATION_ROLL_180_YAW_270 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX # DPS280 or SPL06 integrated on I2C bus BARO DPS280 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/defaults.parm deleted file mode 100644 index 3be3b1414495c..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/defaults.parm +++ /dev/null @@ -1,5 +0,0 @@ -SERVO13_FUNCTION 120 -NTF_LED_BRIGHT 2 -NTF_LED_LEN 8 -CAN_D1_PROTOCOL 1 -CAN_P1_DRIVER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/hwdef-bl.dat deleted file mode 100644 index 5b10f0cd8f961..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/hwdef-bl.dat +++ /dev/null @@ -1 +0,0 @@ -include ../MatekF765-Wing/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/hwdef.dat deleted file mode 100644 index 9588ccb501ca0..0000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF765-SE-bdshot/hwdef.dat +++ /dev/null @@ -1,14 +0,0 @@ -# Bi-directional dshot version of MatekF765-SE - -include ../MatekF765-SE/hwdef.dat - -# undefine the pins we are going to change -undef PA0 PA1 PA2 PA3 - -# hw definition file for processing by chibios_pins.py -# for Matek F765-SE - -PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR -PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) -PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR -PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm new file mode 100644 index 0000000000000..fdd32a445cc13 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm @@ -0,0 +1,22 @@ +# up to 11 motors/servos + +OUT1_FUNCTION 33 +OUT2_FUNCTION 34 +OUT3_FUNCTION 35 +OUT4_FUNCTION 36 +OUT5_FUNCTION 51 +OUT6_FUNCTION 52 +OUT7_FUNCTION 53 +OUT8_FUNCTION 54 +OUT9_FUNCTION 55 +OUT10_FUNCTION 56 +OUT11_FUNCTION 57 + +# DShot 600 +ESC_PWM_TYPE 7 +OUT_BLH_OTYPE 6 + +OUT_BLH_MASK 15 + +# DShot telem on RX3 +ESC_TELEM_PORT 3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef-bl.dat new file mode 100644 index 0000000000000..ec9c59fa8b0fa --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekG474/hwdef-bl.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef.dat new file mode 100644 index 0000000000000..006e5872cfc55 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/hwdef.dat @@ -0,0 +1,22 @@ +include ../MatekG474/hwdef.inc + +# --------------------- PWM ----------------------- +PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PA6 TIM3_CH1 TIM3 PWM(5) GPIO(54) +PA7 TIM3_CH2 TIM3 PWM(6) GPIO(55) +PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56) +PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57) +PC6 TIM8_CH1 TIM8 PWM(9) GPIO(58) +PB9 TIM8_CH3 TIM8 PWM(10) GPIO(59) +PB2 TIM5_CH1 TIM5 PWM(11) GPIO(60) + +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/defaults.parm new file mode 100644 index 0000000000000..170696ab76629 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/defaults.parm @@ -0,0 +1,24 @@ +# ----setup for PORT defaults +#| EMPTY | USART1 | USART2 | USART3 | UART4 | +GPS_PORT 2 +MSP_PORT 3 +RNGFND_PORT 4 +ADSB_PORT -1 +RC_PORT 1 +EFI_PORT -1 +PRX_PORT -1 +ESC_TELEM_PORT -1 + +# ----I2C AirSpeed sensor, disabled by default +ARSPD_BUS 0 # I2C1 +ARSPD_TYPE 0 + +# ----I2C External Baro +BARO_EXT_BUS -1 +BARO_PROBE_EXT 4095 + +# ----I2C BATT_MONITOR INA2xx +BATT_I2C_BUS 0 +BATT_I2C_ADDR 0 +BATT_SHUNT 0.0002 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef-bl.dat new file mode 100644 index 0000000000000..ec9c59fa8b0fa --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekG474/hwdef-bl.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat new file mode 100644 index 0000000000000..c0ca5bcfaeb38 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat @@ -0,0 +1,68 @@ +include ../MatekG474/hwdef.inc + +# ----------- GPS +define HAL_PERIPH_ENABLE_GPS +define GPS_MAX_RATE_MS 200 + +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 + +# allow for F9P GPS modules with moving baseline +define GPS_MOVING_BASELINE 1 + + +# ----------- COMPASS +define HAL_PERIPH_ENABLE_MAG + +SPIDEV rm3100 SPI2 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 + +define HAL_COMPASS_MAX_SENSORS 1 + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + + +# ----------- I2C airspeed +define HAL_PERIPH_ENABLE_AIRSPEED +define AIRSPEED_MAX_SENSORS 1 + + +# ----------- I2C Barometer +define HAL_PERIPH_ENABLE_BARO +define HAL_BARO_ALLOW_INIT_NO_BARO + +# BARO SPL06 I2C:0:0x76 + +# ----------- I2C BATT_MONITOR INA2xx + +define HAL_PERIPH_ENABLE_BATTERY +define AP_BATTERY_INA2XX_ENABLED 1 +define HAL_BATT_MONITOR_DEFAULT 21 + + +# ----------- MSP +define HAL_PERIPH_ENABLE_MSP +define HAL_MSP_ENABLED 1 + + +# ----------- ADSB +define HAL_PERIPH_ENABLE_ADSB + + +# ----------- RC INPUT +define HAL_PERIPH_ENABLE_RCIN 1 + + +# ----------- EFI +define HAL_PERIPH_ENABLE_EFI +define HAL_EFI_ENABLED 1 + + +# ----------- proximity +define HAL_PERIPH_ENABLE_PROXIMITY +define HAL_PROXIMITY_ENABLED 1 + + +# ----------- rangefinder +define HAL_PERIPH_ENABLE_RANGEFINDER + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef-bl.inc new file mode 100644 index 0000000000000..77affead7761c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef-bl.inc @@ -0,0 +1,57 @@ +# hw definition file Matek G474 CAN node + +# MCU class and specific type +MCU STM32G474 STM32G474xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MatekG474 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 32 +FLASH_SIZE_KB 512 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# --------------------------------------------- +PC13 LED_BOOTLOADER OUTPUT LOW # blue +define HAL_LED_ON 0 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 + +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + + +# --------------------------------------------- + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 2500 + +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE +define DMA_RESERVE_SIZE 0 +define HAL_DISABLE_LOOP_DELAY +define HAL_NO_TIMER_THREAD +define HAL_NO_RCIN_THREAD + +define HAL_USE_SERIAL FALSE + +# Add CS pins to ensure they are high in bootloader +PB12 MAG_CS CS +PC14 SPARE_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef.inc new file mode 100644 index 0000000000000..edf92aa344919 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474/hwdef.inc @@ -0,0 +1,115 @@ +# hw definition file for Matek G474 CAN node + +# MCU class and specific type +MCU STM32G474 STM32G474xx + +# bootloader starts firmware at 32k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 36 +FLASH_SIZE_KB 512 + +# store parameters in pages +STORAGE_FLASH_PAGE 16 +define HAL_STORAGE_SIZE 1800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MatekG474 + +# crystal frequency +OSCILLATOR_HZ 8000000 + + +env AP_PERIPH 1 + +define SERIAL_BUFFERS_SIZE 512 +# stack for fast interrupts +define PORT_INT_REQUIRED_STACK 64 + +define HAL_NO_GPIO_IRQ +define HAL_NO_MONITOR_THREAD +define HAL_USE_RTC FALSE +define HAL_DISABLE_LOOP_DELAY +define HAL_NO_GCS +define HAL_NO_LOGGING + + +define DMA_RESERVE_SIZE 2048 + +# don't share any DMA channels (there are enough for everyone) +DMA_NOSHARE * + + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# allow for reboot command for faster development +# define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + + +# blue LED0 marked as ACT +PC13 LED OUTPUT HIGH +define HAL_LED_ON 1 + +# --------------------- SPI1 RM3100 ----------------------- +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 MAG_CS CS +PC14 SPARE_CS CS + +# ---------------------- I2C bus ------------------------ +I2C_ORDER I2C1 I2C2 + +# SWD debugging, disabled for I2C1 +# PA13 JTMS-SWDIO SWD +# PA14 JTCK-SWCLK SWD + +PA13 I2C1_SCL I2C1 +PA14 I2C1_SDA I2C1 + +PC4 I2C2_SCL I2C2 +PA8 I2C2_SDA I2C2 + +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 0 + +define HAL_USE_I2C TRUE + +# ---------------------- CAN bus ------------------------- +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +define HAL_CAN_POOL_SIZE 6000 + +# ---------------------- UARTs --------------------------- +# make the UARTn numbers in parameters match the silkscreen +# | sr0 | sr1 | sr2 | sr3 | sr4 | +SERIAL_ORDER EMPTY USART1 USART2 USART3 UART4 + +PA9 USART1_TX USART1 SPEED_HIGH +PA10 USART1_RX USART1 SPEED_HIGH + +PB3 USART2_TX USART2 SPEED_HIGH +PB4 USART2_RX USART2 SPEED_HIGH + +PB10 USART3_TX USART3 SPEED_HIGH NODMA +PB11 USART3_RX USART3 SPEED_HIGH NODMA + +PC10 UART4_TX UART4 SPEED_HIGH +PC11 UART4_RX UART4 SPEED_HIGH + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# ----------- ADC +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat index 5318c5d3eaebc..12838b5618d90 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef-bl.dat @@ -8,7 +8,7 @@ MCU STM32H7xx STM32H7A3xx APJ_BOARD_ID AP_HW_MatekH7A3 # crystal frequency, setup to use external oscillator -OSCILLATOR_HZ 8000000 +OSCILLATOR_HZ 16000000 FLASH_SIZE_KB 2048 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat index e5544cbddef1b..8d3608e2348da 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat @@ -8,7 +8,7 @@ MCU STM32H7xx STM32H7A3xx APJ_BOARD_ID AP_HW_MatekH7A3 # crystal frequency, setup to use external oscillator -OSCILLATOR_HZ 8000000 +OSCILLATOR_HZ 16000000 FLASH_SIZE_KB 2048 env OPTIMIZE -Os @@ -159,7 +159,7 @@ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ define HAL_LOGGING_DATAFLASH_ENABLED 1 define HAL_OS_FATFS_IO 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV +define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX # ----------------- I2C compass & Baro ----------------- diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/defaults.parm new file mode 100644 index 0000000000000..3c63f226fb8af --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/defaults.parm @@ -0,0 +1,3 @@ +OUT1_FUNCTION 33 +OUT1_MIN 1000 +OUT1_MAX 2000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef-bl.dat new file mode 100644 index 0000000000000..b9005f84941a6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../MatekL431/hwdef-bl.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef.dat new file mode 100644 index 0000000000000..06a9bcde6067a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-APDTelem/hwdef.dat @@ -0,0 +1,17 @@ +include ../MatekL431/hwdef.inc + +define HAL_USE_ADC FALSE + +# --------------------- PWM ----------------------- +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) + +define HAL_PERIPH_ENABLE_RC_OUT + +# enable APD telemetry on rx1 +define HAL_PERIPH_ENABLE_ESC_APD +define APD_ESC_INSTANCES 1 +define APD_ESC_SERIAL_0 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat index 0a2ddad959136..99e189f4b3b39 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat @@ -6,6 +6,7 @@ define HAL_DISABLE_ADC_DRIVER TRUE # support all rangefinder types define HAL_PERIPH_ENABLE_RANGEFINDER +define RANGEFINDER_MAX_INSTANCES 2 define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat index a1c137a68e941..1f973c51961f8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405Mini/hwdef.dat @@ -145,6 +145,9 @@ define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin +# setup for BF migration +define HAL_FRAME_TYPE_DEFAULT 12 + # reduce flash usage include ../include/minimize_fpv_osd.inc undef AP_OPTICALFLOW_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat index 7ee7100f64468..0b102a9a56857 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir405v2/hwdef.dat @@ -151,6 +151,9 @@ define OSD_ENABLED 1 define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin +# setup for BF migration +define HAL_FRAME_TYPE_DEFAULT 12 + # reduce flash usage define HAL_MOUNT_ENABLED 0 define HAL_SPRAYER_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_BackView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_BackView.jpg new file mode 100644 index 0000000000000..45a264ab50d75 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_BackView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_FrontView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_FrontView.jpg new file mode 100644 index 0000000000000..761acf766a538 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_FrontView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_Pinout.xlsx b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_Pinout.xlsx new file mode 100644 index 0000000000000..2025f82d678d0 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_Pinout.xlsx differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_PortsConnection.jpg b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_PortsConnection.jpg new file mode 100644 index 0000000000000..9af8d732cd355 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/MicoAir743_PortsConnection.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/README.md new file mode 100644 index 0000000000000..2c77dec73cc0d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/README.md @@ -0,0 +1,98 @@ +# MicoAir743 Flight Controller + +The MicoAir743 is a flight controller designed and produced by [MicoAir Tech.](http://micoair.com/). + +## Features + + - STM32H743 microcontroller + - BMI088/BMI270 dual IMUs + - DPS310 barometer + - IST8310 magnetometer + - AT7456E OSD + - 9V 3A BEC; 5V 3A BEC + - MicroSD Card Slot + - 7 UARTs + - 10 PWM outputs + - 1 CAN + - 1 I2C + - 1 SWD + +## Physical + +![MicoAir H743 V1.3 Front View](MicoAir743_FrontView.jpg) + +![MicoAir H743 V1.3 Back View](MicoAir743_BackView.jpg) + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART2 (DisplayPort, DMA-enabled) + - SERIAL3 -> UART3 (GPS, DMA-enabled) + - SERIAL4 -> UART4 (MAVLink2, DMA-enabled) + - SERIAL5 -> UART6 (RCIN, DMA-enabled) + - SERIAL6 -> UART7 (RX only, ESC Telemetry, DMA-enabled) + - SERIAL7 -> UART8 (User, DMA-enabled) + + +## RC Input + +The default RC input is configured on the UART6. The SBUS pin is inverted and connected to RX6. Non SBUS, single wire serial inputs can be directly tied to RX6 if SBUS pin is left unconnected. RC could be applied instead at a different UART port such as UART1, UART4 or UART8, and set the protocol to receive RC data: `SERIALn_PROTOCOL=23` and change SERIAL5 _Protocol to something other than '23'. + +## OSD Support + +The MicoAir743 supports onboard OSD using OSD_TYPE 1 (MAX7456 driver). Simultaneously, DisplayPort OSD is available on the HD VTX connector, See below. + + +## VTX Support + +The SH1.0-6P connector supports a DJI Air Unit / HD VTX connection. Protocol defaults to DisplayPort. Pin 1 of the connector is 9v so be careful not to connect this to a peripheral requiring 5v. + +## PWM Output + +The MicoAir743 supports up to 10 PWM outputs. + +All the channels support DShot. + +Channels 1-8 support bi-directional DShot. + +PWM outputs are grouped and every group must use the same output protocol: + +1, 2, 3, 4 are Group 1; + +5, 6 are Group 2; + +7, 8, 9, 10 are Group 3; + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 21.2 + - BATT_CURR_SCALE 40.2 + +## Compass + +The MicoAir743 has a built-in compass sensor (IST8310), and you can also attach an external compass using I2C on the SDA and SCL connector. + +## Mechanical + + - Mounting: 30.5 x 30.5mm, Φ4mm + - Dimensions: 36 x 36 x 8 mm + - Weight: 9g + +## Ports Connector + +![MicoAir H743 V1.3 Ports Connection](MicoAir743_PortsConnection.jpg) + +## 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 favorite 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/MicoAir743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/defaults.parm new file mode 100644 index 0000000000000..99da6e3767652 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/defaults.parm @@ -0,0 +1,11 @@ +#BATTERY MONITOR ON +BATT_MONITOR 4 + +#enable second OSD type +OSD_TYPE2 = 5 + +#Serial Port defaults +SERIAL2_PROTOCOL 42 +SERIAL4_PROTOCOL 2 +SERIAL5_PROTOCOL 23 +SERIAL6_PROTOCOL 16 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef-bl.dat new file mode 100644 index 0000000000000..28a492deb868d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef-bl.dat @@ -0,0 +1,49 @@ +# hw definition file for processing by chibios_hwdef.py +# for the MicoAir743 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MicoAir743 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# flash size +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 128 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PB12 AT7456E_CS CS +PA15 BMI270_CS CS +PD5 GYRO_CS CS +PD4 ACCEL_CS CS + +# LEDs +PE6 LED_ACTIVITY OUTPUT LOW #green +PE4 LED_BOOTLOADER OUTPUT LOW #blue +define HAL_LED_ON 0 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat new file mode 100644 index 0000000000000..b4f966df89a9c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MicoAir743/hwdef.dat @@ -0,0 +1,171 @@ +# hw definition file for processing by chibios_hwdef.py +# for the MicoAir743 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_MicoAir743 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# flash size +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 +STORAGE_FLASH_PAGE 14 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 USART6 UART7 UART8 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 - TELEM1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 - DJIO3 +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# USART3 - GPS +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# UART4 - TELEM2 +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 + +# UART6 - RC_INPUT +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +PD0 SBUS_INV OUTPUT LOW + +# UART7 - ESC +PE7 UART7_RX UART7 + +# UART8 - TELEM3 +PE1 UART8_TX UART8 +PE0 UART8_RX UART8 + +# SWD +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CAN +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +# two I2C bus +I2C_ORDER I2C2 I2C1 + +# I2C1 - CONNECTOR +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C2 - BARO & MAG +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# PWM output pins +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) BIDIR +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PB1 TIM3_CH4 TIM3 PWM(5) GPIO(54) BIDIR +PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55) +PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR +PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57) +PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) +PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) + +# 10 PWM available by default +define BOARD_PWM_COUNT_DEFAULT 10 + +# LEDs +PE5 LED_RED OUTPUT LOW GPIO(0) +PE6 LED_GREEN OUTPUT LOW GPIO(1) +PE4 LED_BLUE OUTPUT LOW GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_GPIO_LED_ON 0 +define HAL_HAVE_PIXRACER_LED + +# ADC for Power +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) + +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 21.12 +define HAL_BATT_CURR_SCALE 40.2 + +# compass +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_NONE +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_90 + +# barometers +BARO DPS310 I2C:0:0x76 + +# microSD support +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +define FATFS_HAL_DEVICE SDCD1 + +# SPI1 - AT7456E +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PB12 AT7456E_CS CS + +# SPI2 - IMUs +PD3 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 +PD5 GYRO_CS CS +PD4 ACCEL_CS CS +PA15 BMI270_CS CS + +# SPI devices +SPIDEV bmi088_a SPI2 DEVID1 ACCEL_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI2 DEVID2 GYRO_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi270 SPI2 DEVID3 BMI270_CS MODE3 1*MHZ 10*MHZ +SPIDEV osd SPI1 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ + +# 2 IMUs +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_270 +IMU BMI270 SPI:bmi270 ROTATION_ROLL_180 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# setup for OSD +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# setup for BF migration +define HAL_FRAME_TYPE_DEFAULT 12 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_BackView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_BackView.jpg new file mode 100644 index 0000000000000..0c134b8abfc80 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_BackView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_FrontView.jpg b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_FrontView.jpg new file mode 100644 index 0000000000000..061d96c320f60 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_FrontView.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_Pinout.xlsx b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_Pinout.xlsx new file mode 100644 index 0000000000000..ba131825ff922 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/NxtPX4v2_Pinout.xlsx differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/README.md new file mode 100644 index 0000000000000..2e20e8d314d55 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/README.md @@ -0,0 +1,92 @@ +# NxtPX4v2 Flight Controller + +The NxtPX4v2 is an open-source hardware designed and maintened by [HKUST UAV-Group](https://github.com/HKUST-Aerial-Robotics/Nxt-FC). And it is produced by [MicoAir Tech.](http://micoair.com/). + +## Features + + - STM32H743 microcontroller + - BMI088+BMI088(DUAL) IMU + - SPL06 barometer + - 12V 2.5A BEC; 5V 2.5A BEC + - SDCard +- 7x UART +- 8x PWM +- 1x I2C +- 1x SPI +- 1x SWD + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART2 (MAVLink2, DMA-enabled) + - SERIAL2 -> UART4 (MAVLink2, DMA-enabled) + - SERIAL3 -> UART1 (GPS, DMA-enabled) + - SERIAL4 -> UART3 (VTX-HD, DMA-enabled) + - SERIAL5 -> UART7 (ESC Telemetry, DMA-enabled) + - SERIAL6 -> UART5 (RCIN, DMA-enabled) + - SERIAL7 -> UART8 (DMA-enabled) + +## RC Input + +The default RC input is configured on the UART5. The SBUS pin is inverted and connected to RX5. Non SBUS, single wire serial inputs can be directly tied to RX5 if SBUS pin is left unconnected. RC could be applied instead at a different UART port such as UART2, UART4 or UART8, and set the protocol to receive RC data: `SERIALn_PROTOCOL=23` and change SERIAL6 _Protocol to something other than '23' + +## VTX Support + +The SH1.0-6P connector supports a DJI Air Unit / HD VTX connection. Protocol defaults to DisplayPort. Pin 1 of the connector is 12v so be careful not to connect this to a peripheral requiring 5v. + +## PWM Output + +The NxtPX4v2 supports up to 8 PWM outputs. All channels support bi-directional DShot. + +PWM outputs are grouped and every group must use the same output protocol: + +1, 2, 3, 4 are Group1; + +5, 6 are Group 2; + +7, 8 are Group 3; + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 4 + - BATT_CURR_PIN 8 + - BATT_VOLT_MULT 10.2 + - BATT_CURR_SCALE 20.4 + +## Compass + +The NxtPX4v2 does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL connector. + +## GPIOs + +The remaining 3 outputs (labelled AUX1 to AUX3) are the "auxiliary" outputs. These are directly attached to the STM32H743. + +The numbering of the GPIOs for PIN variables in ardupilot is: + + - AUX1 - PA4 - 81 + - AUX2 - PC1 - 82 + - AUX3 - PC0 - 83 + +## Physical + + - Mounting: 20 x 20mm, Φ3mm +- Dimensions: 27 x 32 x 8 mm +- Weight: 6.5g + +## Ports Connector + +![NxtPX4v2 Front View](NxtPX4v2_FrontView.jpg) + +![NxtPX4v2 Back View](NxtPX4v2_BackView.jpg) + +## 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 favorite 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/NxtPX4v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/defaults.parm new file mode 100644 index 0000000000000..7bc08c2ca66fd --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/defaults.parm @@ -0,0 +1,10 @@ +#BATTERY MONITOR ON +BATT_MONITOR 4 + +#Serial Port defaults +SERIAL4_PROTOCOL 42 +SERIAL5_PROTOCOL 16 +SERIAL6_PROTOCOL 23 + +#MSP DisplayPort enable +OSD_TYPE 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef-bl.dat new file mode 100644 index 0000000000000..887f3b99bcde9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef-bl.dat @@ -0,0 +1,45 @@ +# hw definition file for processing by chibios_hwdef.py +# for the NxtPX4v2 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_NxtPX4v2 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# flash size +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 128 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PA3 BMI088_1_G_CS CS +PA2 BMI088_1_A_CS CS +PC2 BMI088_2_G_CS CS +PC13 BMI088_2_A_CS CS + +# LEDs +PD11 LED_ACTIVITY OUTPUT HIGH GPIO(91) #green +PB15 LED_BOOTLOADER OUTPUT HIGH GPIO(92) #blue +define HAL_LED_ON 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef.dat new file mode 100644 index 0000000000000..30877ff33f8c8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/NxtPX4v2/hwdef.dat @@ -0,0 +1,163 @@ +# hw definition file for processing by chibios_hwdef.py +# for the NxtPX4v2 hardware + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_NxtPX4v2 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 12 +define CH_CFG_ST_RESOLUTION 16 + +# flash size +FLASH_SIZE_KB 2048 +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 +STORAGE_FLASH_PAGE 14 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 UART4 USART1 USART3 UART7 UART5 UART8 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 +PD0 VBUS INPUT OPENDRAIN + +# GPS1 +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +# TELEM1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 + +# DJI O3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# TELEM2 +PB9 UART4_TX UART4 +PB8 UART4_RX UART4 + +# RC_INPUT +PB13 UART5_TX UART5 +PB12 UART5_RX UART5 +PD14 SBUS_INV OUTPUT LOW + +# ESC +PE7 UART7_RX UART7 + +# TELEM3 +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# SWD +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# two I2C bus +I2C_ORDER I2C1 I2C4 + +# I2C1 - baro +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# I2C4 - CONNECTOR +PD12 I2C4_SCL I2C4 +PD13 I2C4_SDA I2C4 + +# PWM output pins +PE9 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR +PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) +PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR +PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) +PB10 TIM2_CH3 TIM2 PWM(5) GPIO(54) BIDIR +PB11 TIM2_CH4 TIM2 PWM(6) GPIO(55) +PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56) BIDIR +PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57) + +# GPIOs +PA4 PINIO1 OUTPUT GPIO(81) LOW +PC1 PINIO2 OUTPUT GPIO(82) LOW +PC0 PINIO3 OUTPUT GPIO(83) LOW + +# LEDs +PD15 LED_RED OUTPUT HIGH GPIO(90) +PD11 LED_GREEN OUTPUT HIGH GPIO(91) +PB15 LED_BLUE OUTPUT HIGH GPIO(92) + +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_B_LED_PIN 91 +define HAL_GPIO_C_LED_PIN 92 + +define HAL_GPIO_LED_ON 1 +define HAL_HAVE_PIXRACER_LED + +# ADC for Power +PC4 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC5 BATT_CURRENT_SENS ADC2 SCALE(1) + +define HAL_BATT_VOLT_PIN 4 +define HAL_BATT_CURR_PIN 8 +define HAL_BATT_VOLT_SCALE 10.2 +define HAL_BATT_CURR_SCALE 20.4 + +# 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 + +# microSD support +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +define FATFS_HAL_DEVICE SDCD1 + +# SPI1 - IMU0 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA3 BMI088_1_G_CS CS +PA2 BMI088_1_A_CS CS + +# SPI3 - CONNECTOR +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB2 SPI3_MOSI SPI3 + +# SPI4 - IMU1 +PE6 SPI4_MOSI SPI4 +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PC2 BMI088_2_G_CS CS +PC13 BMI088_2_A_CS CS + +# barometers +BARO SPL06 I2C:0:0x77 + +# SPI devices +SPIDEV imu0_a SPI1 DEVID1 BMI088_1_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu0_g SPI1 DEVID2 BMI088_1_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu1_a SPI4 DEVID3 BMI088_2_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV imu1_g SPI4 DEVID4 BMI088_2_G_CS MODE3 10*MHZ 10*MHZ + +# 2 IMUs +IMU BMI088 SPI:imu0_a SPI:imu0_g ROTATION_ROLL_180_YAW_90 +IMU BMI088 SPI:imu1_a SPI:imu1_g ROTATION_ROLL_180_YAW_90 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" 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/Sierra-TrueNavPro-G4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat index 3015e7714c02f..5162c63078672 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat @@ -104,7 +104,7 @@ env ROMFS_UNCOMPRESSED True # PWM, WS2812 LED PA3 TIM2_CH4 TIM2 PWM(1) -DMA_NOSHARE USART2* +DMA_NOSHARE USART2* SPI1* define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro-G4" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c index 3f81cc9ce1ef9..769eea6799370 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c @@ -520,10 +520,16 @@ bool stm32_flash_erasepage(uint32_t page) FLASH->CR |= FLASH_CR_STRT; #elif defined(STM32G4) FLASH->CR = FLASH_CR_PER; - // rather oddly, PNB is a 7 bit field that the ref manual says can - // contain 8 bits we assume that for 512k single bank devices - // there is an 8th bit +#ifdef FLASH_CR_BKER_Pos + /* + we assume dual bank mode, we set the bottom 7 bits of the page + into PNB and the 8th bit into BKER + */ + FLASH->CR |= (page&0x7F)<>7)<CR |= page<CR |= FLASH_CR_STRT; #elif defined(STM32L4PLUS) FLASH->CR |= FLASH_CR_PER; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 8744b43a3896f..4e1e04a75563e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -2613,14 +2613,6 @@ def write_hwdef_header(self, outfilename): self.embed_bootloader(f) - if len(self.romfs) > 0: - # Allow lua to load from ROMFS if any lua files are added - for file in self.romfs.keys(): - if file.startswith("scripts") and file.endswith(".lua"): - f.write('#define HAL_HAVE_AP_ROMFS_EMBEDDED_LUA 1\n') - break - f.write('#define HAL_HAVE_AP_ROMFS_EMBEDDED_H 1\n') - if self.mcu_series.startswith('STM32F1'): f.write(''' /* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat index 602edd8721cb7..12c3bc9f1bf59 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat @@ -109,11 +109,15 @@ IMU Invensense SPI:icm20789 ROTATION_NONE # radio IRQ is on GPIO(100) define HAL_GPIO_RADIO_IRQ 100 -define HAL_RCINPUT_WITH_AP_RADIO 1 +define AP_RADIO_ENABLED 1 define AP_RADIO_BACKEND_DEFAULT_ENABLED 0 define AP_RADIO_CC2500_ENABLED 1 define AP_RADIO_CYRF6936_ENABLED 1 +define AP_RCPROTOCOL_ENABLED 1 +define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +define AP_RCPROTOCOL_RADIO_ENABLED 1 + STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 15360 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat index a6711bd7eafb2..0a772b36885ec 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat @@ -99,12 +99,16 @@ IMU Invensense I2C:1:0x68 ROTATION_NONE # radio IRQ is on GPIO(100) define HAL_GPIO_RADIO_IRQ 100 -define HAL_RCINPUT_WITH_AP_RADIO 1 +define AP_RADIO_ENABLED 1 define AP_RADIO_BACKEND_DEFAULT_ENABLED 0 define AP_RADIO_CC2500_ENABLED 1 define AP_RADIO_CYRF6936_ENABLED 1 define AP_RADIO_BK2425_ENABLED 1 +define AP_RCPROTOCOL_ENABLED 1 +define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +define AP_RCPROTOCOL_RADIO_ENABLED 1 + STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 15360 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index e6bc82ba767e0..0bba9c42cdb01 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -31,7 +31,7 @@ define CHIBIOS_SHORT_BOARD_NAME "skyviper-v245" SERIAL_ORDER OTG1 USART2 EMPTY UART4 # enable AP_Radio support -define HAL_RCINPUT_WITH_AP_RADIO 1 +define AP_RADIO_ENABLED 1 define AP_RADIO_BACKEND_DEFAULT_ENABLED 0 define AP_RADIO_CC2500_ENABLED 1 define AP_RADIO_CYRF6936_ENABLED 1 @@ -170,7 +170,9 @@ define AP_CAMERA_BACKEND_DEFAULT_ENABLED 0 define AP_CAMERA_MAVLINK_ENABLED 1 # SkyViper uses AP_Radio, which does its own RC protocol decoding: -define AP_RCPROTOCOL_ENABLED 0 +define AP_RCPROTOCOL_ENABLED 1 +define AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED 0 +define AP_RCPROTOCOL_RADIO_ENABLED 1 // few prelcnad backends are applicable define AC_PRECLAND_BACKEND_DEFAULT_ENABLED 0 diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index 974e6523e4a61..74d300185e0f8 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -8,237 +8,64 @@ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_CANZERO -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - #include "GPIO.h" +#include "GPIO_RPI.h" +#include "GPIO_RPI_BCM.h" +#include "GPIO_RPI_RP1.h" #include "Util_RPI.h" -#define GPIO_RPI_MAX_NUMBER_PINS 32 - -using namespace Linux; - extern const AP_HAL::HAL& hal; -// Range based in the first memory address of the first register and the last memory addres -// for the GPIO section (0x7E20'00B4 - 0x7E20'0000). -const uint8_t GPIO_RPI::_gpio_registers_memory_range = 0xB4; -const char* GPIO_RPI::_system_memory_device_path = "/dev/mem"; +using namespace Linux; GPIO_RPI::GPIO_RPI() { } -void GPIO_RPI::set_gpio_mode_alt(int pin, int alternative) -{ - // Each register can contain 10 pins - const uint8_t pins_per_register = 10; - // Calculates the position of the 3 bit mask in the 32 bits register - const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; - /** Creates a mask to enable the alternative function based in the following logic: - * - * | Alternative Function | 3 bits value | - * |:--------------------:|:------------:| - * | Function 0 | 0b100 | - * | Function 1 | 0b101 | - * | Function 2 | 0b110 | - * | Function 3 | 0b111 | - * | Function 4 | 0b011 | - * | Function 5 | 0b010 | - */ - const uint8_t alternative_value = - (alternative < 4 ? (alternative + 4) : (alternative == 4 ? 3 : 2)); - // 0b00'000'000'000'000'000'000'ALT'000'000'000 enables alternative for the 4th pin - const uint32_t mask_with_alt = static_cast(alternative_value) << tree_bits_position_in_register; - const uint32_t mask = 0b111 << tree_bits_position_in_register; - // Clear all bits in our position and apply our mask with alt values - uint32_t register_value = _gpio[pin / pins_per_register]; - register_value &= ~mask; - _gpio[pin / pins_per_register] = register_value | mask_with_alt; -} - -void GPIO_RPI::set_gpio_mode_in(int pin) -{ - // Each register can contain 10 pins - const uint8_t pins_per_register = 10; - // Calculates the position of the 3 bit mask in the 32 bits register - const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; - // Create a mask that only removes the bits in this specific GPIO pin, E.g: - // 0b11'111'111'111'111'111'111'000'111'111'111 for the 4th pin - const uint32_t mask = ~(0b111<(address) + static_cast(offset); -} - -volatile uint32_t* GPIO_RPI::get_memory_pointer(uint32_t address, uint32_t range) const -{ - auto pointer = mmap( - nullptr, // Any adddress in our space will do - range, // Map length - PROT_READ|PROT_WRITE|PROT_EXEC, // Enable reading & writing to mapped memory - MAP_SHARED|MAP_LOCKED, // Shared with other processes - _system_memory_device, // File to map - address // Offset to GPIO peripheral - ); - - if (pointer == MAP_FAILED) { - return nullptr; - } - - return static_cast(pointer); -} - -bool GPIO_RPI::openMemoryDevice() -{ - _system_memory_device = open(_system_memory_device_path, O_RDWR|O_SYNC|O_CLOEXEC); - if (_system_memory_device < 0) { - AP_HAL::panic("Can't open %s", GPIO_RPI::_system_memory_device_path); - return false; - } - - return true; -} - -void GPIO_RPI::closeMemoryDevice() -{ - close(_system_memory_device); - // Invalidate device variable - _system_memory_device = -1; -} - void GPIO_RPI::init() { const LINUX_BOARD_TYPE rpi_version = UtilRPI::from(hal.util)->detect_linux_board_type(); - GPIO_RPI::Address peripheral_base; - if(rpi_version == LINUX_BOARD_TYPE::RPI_ZERO_1) { - peripheral_base = Address::BCM2708_PERIPHERAL_BASE; - } else if (rpi_version == LINUX_BOARD_TYPE::RPI_2_3_ZERO2) { - peripheral_base = Address::BCM2709_PERIPHERAL_BASE; - } else if (rpi_version == LINUX_BOARD_TYPE::RPI_4) { - peripheral_base = Address::BCM2711_PERIPHERAL_BASE; - } else { - AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); - return; - } - - if (!openMemoryDevice()) { - AP_HAL::panic("Failed to initialize memory device."); - return; - } - - const uint32_t gpio_address = get_address(peripheral_base, PeripheralOffset::GPIO); - - _gpio = get_memory_pointer(gpio_address, _gpio_registers_memory_range); - if (!_gpio) { - AP_HAL::panic("Failed to get GPIO memory map."); + switch (rpi_version) { + case LINUX_BOARD_TYPE::RPI_ZERO_1: + case LINUX_BOARD_TYPE::RPI_2_3_ZERO2: + case LINUX_BOARD_TYPE::RPI_4: + gpioDriver = new GPIO_RPI_BCM(); + gpioDriver->init(); + break; + case LINUX_BOARD_TYPE::RPI_5: + gpioDriver = new GPIO_RPI_RP1(); + gpioDriver->init(); + break; + default: + AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); + return; } - - // No need to keep mem_fd open after mmap - closeMemoryDevice(); } void GPIO_RPI::pinMode(uint8_t pin, uint8_t output) { - if (output == HAL_GPIO_INPUT) { - set_gpio_mode_in(pin); - } else { - set_gpio_mode_in(pin); - set_gpio_mode_out(pin); - } + gpioDriver->pinMode(pin, output); } void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt) { - if (output == HAL_GPIO_INPUT) { - set_gpio_mode_in(pin); - } else if (output == HAL_GPIO_ALT) { - set_gpio_mode_in(pin); - set_gpio_mode_alt(pin, alt); - } else { - set_gpio_mode_in(pin); - set_gpio_mode_out(pin); - } + gpioDriver->pinMode(pin, output, alt); } uint8_t GPIO_RPI::read(uint8_t pin) { - if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { - return 0; - } - return static_cast(get_gpio_logic_state(pin)); + return gpioDriver->read(pin); } void GPIO_RPI::write(uint8_t pin, uint8_t value) { - if (value != 0) { - set_gpio_high(pin); - } else { - set_gpio_low(pin); - } + gpioDriver->write(pin, value); } void GPIO_RPI::toggle(uint8_t pin) { - if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { - return ; - } - uint32_t flag = (1 << pin); - _gpio_output_port_status ^= flag; - write(pin, (_gpio_output_port_status & flag) >> pin); + gpioDriver->toggle(pin); } /* Alternative interface: */ diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.h b/libraries/AP_HAL_Linux/GPIO_RPI.h index f694dce679041..ac934a42ef841 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.h +++ b/libraries/AP_HAL_Linux/GPIO_RPI.h @@ -2,6 +2,7 @@ #include #include "AP_HAL_Linux.h" +#include "GPIO_RPI_HAL.h" /** * @brief Check for valid Raspberry Pi pin range @@ -15,13 +16,12 @@ template constexpr uint8_t RPI_GPIO_() return pin; } + namespace Linux { /** * @brief Class for Raspberry PI GPIO control * - * For more information: https://elinux.org/RPi_BCM2835_GPIOs - * */ class GPIO_RPI : public AP_HAL::GPIO { public: @@ -40,161 +40,7 @@ class GPIO_RPI : public AP_HAL::GPIO { bool usb_connected(void) override; private: - // Raspberry Pi BASE memory address - enum class Address : uint32_t { - BCM2708_PERIPHERAL_BASE = 0x20000000, // Raspberry Pi 0/1 - BCM2709_PERIPHERAL_BASE = 0x3F000000, // Raspberry Pi 2/3 - BCM2711_PERIPHERAL_BASE = 0xFE000000, // Raspberry Pi 4 - }; - - // Offset between peripheral base address - enum class PeripheralOffset : uint32_t { - GPIO = 0x200000, - }; - - /** - * @brief Open memory device to allow gpio address access - * Should be used before get_memory_pointer calls in the initialization - * - * @return true - * @return false - */ - bool openMemoryDevice(); - - /** - * @brief Close open memory device - * - */ - void closeMemoryDevice(); - - /** - * @brief Return pointer to memory location with specific range access - * - * @param address - * @param range - * @return volatile uint32_t* - */ - volatile uint32_t* get_memory_pointer(uint32_t address, uint32_t range) const; - - /** - * @brief Get memory address based in base address and peripheral offset - * - * @param address - * @param offset - * @return uint32_t - */ - uint32_t get_address(GPIO_RPI::Address address, GPIO_RPI::PeripheralOffset offset) const; - - /** - * @brief Change functionality of GPIO Function Select Registers (GPFSELn) to any alternative function. - * Each GPIO pin is mapped to 3 bits inside a 32 bits register, E.g: - * - * 0b00...'010'101 - * ││ │││ ││└── GPIO Pin N, 1st bit, LSBit - * ││ │││ │└─── GPIO Pin N, 2nd bit - * ││ │││ └──── GPIO Pin N, 3rd bit, MSBit - * ││ ││└────── GPIO Pin N+1, 1st bit, LSBit - * ││ │└─────── GPIO Pin N+1, 2nd bit, - * ││ └──────── GPIO Pin N+1, 3rd bit, MSBit - * ││ ... - * │└───────────── Reserved - * └────────────── Reserved - * - * And the value of this 3 bits selects the functionality of the GPIO pin, E.g: - * 000 = GPIO Pin N is an input - * 001 = GPIO Pin N is an output - * 100 = GPIO Pin N takes alternate function 0 - * 101 = GPIO Pin N takes alternate function 1 - * 110 = GPIO Pin N takes alternate function 2 - * 111 = GPIO Pin N takes alternate function 3 - * 011 = GPIO Pin N takes alternate function 4 - * 010 = GPIO Pin N takes alternate function 5 - * - * The alternative functions are defined in the BCM datasheet under "Alternative Function" - * section for each pin. - * - * This information is also valid for: - * - Linux::GPIO_RPI::set_gpio_mode_in - * - Linux::GPIO_RPI::set_gpio_mode_out - * - * @param pin - */ - void set_gpio_mode_alt(int pin, int alternative); - - /** - * @brief Set a specific GPIO as input - * Check Linux::GPIO_RPI::set_gpio_mode_alt for more information. - * - * @param pin - */ - void set_gpio_mode_in(int pin); - - /** - * @brief Set a specific GPIO as output - * Check Linux::GPIO_RPI::set_gpio_mode_alt for more information. - * - * @param pin - */ - void set_gpio_mode_out(int pin); - - /** - * @brief Modify GPSET0 (GPIO Pin Output Set 0) register to set pin as high - * Writing zero to this register has no effect, please use Linux::GPIO_RPI::set_gpio_low - * to set pin as low. - * - * GPSET0 is a 32bits register that each bit points to a respective GPIO pin: - * 0b...101 - * ││└── GPIO Pin 1, 1st bit, LSBit, defined as High - * │└─── GPIO Pin 2, 2nd bit, No effect - * └──── GPIO Pin 3, 3rd bit, defined as High - * ... - * - * @param pin - */ - void set_gpio_high(int pin); - - /** - * @brief Modify GPCLR0 (GPIO Pin Output Clear 0) register to set pin as low - * Writing zero to this register has no effect, please use Linux::GPIO_RPI::set_gpio_high - * to set pin as high. - * - * GPCLR0 is a 32bits register that each bit points to a respective GPIO pin: - * 0b...101 - * ││└── GPIO Pin 1, 1st bit, LSBit, defined as Low - * │└─── GPIO Pin 2, 2nd bit, No effect - * └──── GPIO Pin 3, 3rd bit, defined as Low - * - * @param pin - */ - void set_gpio_low(int pin); - - /** - * @brief Read GPLEV0 (GPIO Pin Level 0) register check the logic state of a specific pin - * - * GPLEV0 is a 32bits register that each bit points to a respective GPIO pin: - * 0b...101 - * ││└── GPIO Pin 1, 1st bit, LSBit, Pin is in High state - * │└─── GPIO Pin 2, 2nd bit, Pin is in Low state - * └──── GPIO Pin 3, 3rd bit, Pin is in High state - * - * @param pin - * @return true - * @return false - */ - bool get_gpio_logic_state(int pin); - - // Memory pointer to gpio registers - volatile uint32_t* _gpio; - // Memory range for the gpio registers - static const uint8_t _gpio_registers_memory_range; - // Path to memory device (E.g: /dev/mem) - static const char* _system_memory_device_path; - // File descriptor for the memory device file - // If it's negative, then there was an error opening the file. - int _system_memory_device; - // store GPIO output status. - uint32_t _gpio_output_port_status = 0x00; - + GPIO_RPI_HAL* gpioDriver; }; } diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_BCM.cpp b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.cpp new file mode 100644 index 0000000000000..38f20237ff55e --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.cpp @@ -0,0 +1,241 @@ +#include + +#include +#include +#include +#include +#include + +#include "GPIO.h" +#include "Util_RPI.h" +#include "GPIO_RPI_BCM.h" + +#define GPIO_RPI_MAX_NUMBER_PINS 32 + +using namespace Linux; + +extern const AP_HAL::HAL& hal; + +// Range based in the first memory address of the first register and the last memory addres +// for the GPIO section (0x7E20'00B4 - 0x7E20'0000). +const uint8_t GPIO_RPI_BCM::_gpio_registers_memory_range = 0xB4; +const char* GPIO_RPI_BCM::_system_memory_device_path = "/dev/mem"; + +GPIO_RPI_BCM::GPIO_RPI_BCM() +{ +} + +void GPIO_RPI_BCM::set_gpio_mode_alt(int pin, int alternative) +{ + // Each register can contain 10 pins + const uint8_t pins_per_register = 10; + // Calculates the position of the 3 bit mask in the 32 bits register + const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; + /** Creates a mask to enable the alternative function based in the following logic: + * + * | Alternative Function | 3 bits value | + * |:--------------------:|:------------:| + * | Function 0 | 0b100 | + * | Function 1 | 0b101 | + * | Function 2 | 0b110 | + * | Function 3 | 0b111 | + * | Function 4 | 0b011 | + * | Function 5 | 0b010 | + */ + const uint8_t alternative_value = + (alternative < 4 ? (alternative + 4) : (alternative == 4 ? 3 : 2)); + // 0b00'000'000'000'000'000'000'ALT'000'000'000 enables alternative for the 4th pin + const uint32_t mask_with_alt = static_cast(alternative_value) << tree_bits_position_in_register; + const uint32_t mask = 0b111 << tree_bits_position_in_register; + // Clear all bits in our position and apply our mask with alt values + uint32_t register_value = _gpio[pin / pins_per_register]; + register_value &= ~mask; + _gpio[pin / pins_per_register] = register_value | mask_with_alt; +} + +void GPIO_RPI_BCM::set_gpio_mode_in(int pin) +{ + // Each register can contain 10 pins + const uint8_t pins_per_register = 10; + // Calculates the position of the 3 bit mask in the 32 bits register + const uint8_t tree_bits_position_in_register = (pin%pins_per_register)*3; + // Create a mask that only removes the bits in this specific GPIO pin, E.g: + // 0b11'111'111'111'111'111'111'000'111'111'111 for the 4th pin + const uint32_t mask = ~(0b111<(address) + static_cast(offset); +} + +volatile uint32_t* GPIO_RPI_BCM::get_memory_pointer(uint32_t address, uint32_t range) const +{ + auto pointer = mmap( + nullptr, // Any adddress in our space will do + range, // Map length + PROT_READ|PROT_WRITE|PROT_EXEC, // Enable reading & writing to mapped memory + MAP_SHARED|MAP_LOCKED, // Shared with other processes + _system_memory_device, // File to map + address // Offset to GPIO peripheral + ); + + if (pointer == MAP_FAILED) { + return nullptr; + } + + return static_cast(pointer); +} + +bool GPIO_RPI_BCM::openMemoryDevice() +{ + _system_memory_device = open(_system_memory_device_path, O_RDWR|O_SYNC|O_CLOEXEC); + if (_system_memory_device < 0) { + AP_HAL::panic("Can't open %s", GPIO_RPI_BCM::_system_memory_device_path); + return false; + } + + return true; +} + +void GPIO_RPI_BCM::closeMemoryDevice() +{ + close(_system_memory_device); + // Invalidate device variable + _system_memory_device = -1; +} + +void GPIO_RPI_BCM::init() +{ + const LINUX_BOARD_TYPE rpi_version = UtilRPI::from(hal.util)->detect_linux_board_type(); + + GPIO_RPI_BCM::Address peripheral_base; + if(rpi_version == LINUX_BOARD_TYPE::RPI_ZERO_1) { + peripheral_base = Address::BCM2708_PERIPHERAL_BASE; + } else if (rpi_version == LINUX_BOARD_TYPE::RPI_2_3_ZERO2) { + peripheral_base = Address::BCM2709_PERIPHERAL_BASE; + } else if (rpi_version == LINUX_BOARD_TYPE::RPI_4) { + peripheral_base = Address::BCM2711_PERIPHERAL_BASE; + } else { + AP_HAL::panic("Unknown rpi_version, cannot locate peripheral base address"); + return; + } + + if (!openMemoryDevice()) { + AP_HAL::panic("Failed to initialize memory device."); + return; + } + + const uint32_t gpio_address = get_address(peripheral_base, PeripheralOffset::GPIO); + + _gpio = get_memory_pointer(gpio_address, _gpio_registers_memory_range); + if (!_gpio) { + AP_HAL::panic("Failed to get GPIO memory map."); + } + + // No need to keep mem_fd open after mmap + closeMemoryDevice(); +} + +void GPIO_RPI_BCM::pinMode(uint8_t pin, uint8_t output) +{ + if (output == HAL_GPIO_INPUT) { + set_gpio_mode_in(pin); + } else { + set_gpio_mode_in(pin); + set_gpio_mode_out(pin); + } +} + +void GPIO_RPI_BCM::pinMode(uint8_t pin, uint8_t output, uint8_t alt) +{ + if (output == HAL_GPIO_INPUT) { + set_gpio_mode_in(pin); + } else if (output == HAL_GPIO_ALT) { + set_gpio_mode_in(pin); + set_gpio_mode_alt(pin, alt); + } else { + set_gpio_mode_in(pin); + set_gpio_mode_out(pin); + } +} + +uint8_t GPIO_RPI_BCM::read(uint8_t pin) +{ + if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { + return 0; + } + return static_cast(get_gpio_logic_state(pin)); +} + +void GPIO_RPI_BCM::write(uint8_t pin, uint8_t value) +{ + if (value != 0) { + set_gpio_high(pin); + } else { + set_gpio_low(pin); + } +} + +void GPIO_RPI_BCM::toggle(uint8_t pin) +{ + if (pin >= GPIO_RPI_MAX_NUMBER_PINS) { + return ; + } + uint32_t flag = (1 << pin); + _gpio_output_port_status ^= flag; + write(pin, (_gpio_output_port_status & flag) >> pin); +} + +/* Alternative interface: */ +AP_HAL::DigitalSource* GPIO_RPI_BCM::channel(uint16_t n) +{ + return new DigitalSource(n); +} + +bool GPIO_RPI_BCM::usb_connected(void) +{ + return false; +} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_BCM.h b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.h new file mode 100644 index 0000000000000..f0bf6c293bfd7 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_BCM.h @@ -0,0 +1,188 @@ +#pragma once + +#include +#include "GPIO_RPI_HAL.h" + +namespace Linux { + +/** + * @brief Class for Raspberry PI GPIO control + * + * For more information: https://elinux.org/RPi_BCM2835_GPIOs + * + */ +class GPIO_RPI_BCM : public GPIO_RPI_HAL { +public: + GPIO_RPI_BCM(); + void init() override; + void pinMode(uint8_t pin, uint8_t output) override; + void pinMode(uint8_t pin, uint8_t output, uint8_t alt) override; + uint8_t read(uint8_t pin) override; + void write(uint8_t pin, uint8_t value) override; + void toggle(uint8_t pin) override; + + /* Alternative interface: */ + AP_HAL::DigitalSource* channel(uint16_t n); + + /* return true if USB cable is connected */ + bool usb_connected(void); + +private: + // Raspberry Pi BASE memory address + enum class Address : uint32_t { + BCM2708_PERIPHERAL_BASE = 0x20000000, // Raspberry Pi 0/1 + BCM2709_PERIPHERAL_BASE = 0x3F000000, // Raspberry Pi 2/3 + BCM2711_PERIPHERAL_BASE = 0xFE000000, // Raspberry Pi 4 + }; + + // Offset between peripheral base address + enum class PeripheralOffset : uint32_t { + GPIO = 0x200000, + }; + + /** + * @brief Open memory device to allow gpio address access + * Should be used before get_memory_pointer calls in the initialization + * + * @return true + * @return false + */ + bool openMemoryDevice(); + + /** + * @brief Close open memory device + * + */ + void closeMemoryDevice(); + + /** + * @brief Return pointer to memory location with specific range access + * + * @param address + * @param range + * @return volatile uint32_t* + */ + volatile uint32_t* get_memory_pointer(uint32_t address, uint32_t range) const; + + /** + * @brief Get memory address based in base address and peripheral offset + * + * @param address + * @param offset + * @return uint32_t + */ + uint32_t get_address(GPIO_RPI_BCM::Address address, GPIO_RPI_BCM::PeripheralOffset offset) const; + + /** + * @brief Change functionality of GPIO Function Select Registers (GPFSELn) to any alternative function. + * Each GPIO pin is mapped to 3 bits inside a 32 bits register, E.g: + * + * 0b00...'010'101 + * ││ │││ ││└── GPIO Pin N, 1st bit, LSBit + * ││ │││ │└─── GPIO Pin N, 2nd bit + * ││ │││ └──── GPIO Pin N, 3rd bit, MSBit + * ││ ││└────── GPIO Pin N+1, 1st bit, LSBit + * ││ │└─────── GPIO Pin N+1, 2nd bit, + * ││ └──────── GPIO Pin N+1, 3rd bit, MSBit + * ││ ... + * │└───────────── Reserved + * └────────────── Reserved + * + * And the value of this 3 bits selects the functionality of the GPIO pin, E.g: + * 000 = GPIO Pin N is an input + * 001 = GPIO Pin N is an output + * 100 = GPIO Pin N takes alternate function 0 + * 101 = GPIO Pin N takes alternate function 1 + * 110 = GPIO Pin N takes alternate function 2 + * 111 = GPIO Pin N takes alternate function 3 + * 011 = GPIO Pin N takes alternate function 4 + * 010 = GPIO Pin N takes alternate function 5 + * + * The alternative functions are defined in the BCM datasheet under "Alternative Function" + * section for each pin. + * + * This information is also valid for: + * - Linux::GPIO_RPI_BCM::set_gpio_mode_in + * - Linux::GPIO_RPI_BCM::set_gpio_mode_out + * + * @param pin + */ + void set_gpio_mode_alt(int pin, int alternative); + + /** + * @brief Set a specific GPIO as input + * Check Linux::GPIO_RPI_BCM::set_gpio_mode_alt for more information. + * + * @param pin + */ + void set_gpio_mode_in(int pin); + + /** + * @brief Set a specific GPIO as output + * Check Linux::GPIO_RPI_BCM::set_gpio_mode_alt for more information. + * + * @param pin + */ + void set_gpio_mode_out(int pin); + + /** + * @brief Modify GPSET0 (GPIO Pin Output Set 0) register to set pin as high + * Writing zero to this register has no effect, please use Linux::GPIO_RPI_BCM::set_gpio_low + * to set pin as low. + * + * GPSET0 is a 32bits register that each bit points to a respective GPIO pin: + * 0b...101 + * ││└── GPIO Pin 1, 1st bit, LSBit, defined as High + * │└─── GPIO Pin 2, 2nd bit, No effect + * └──── GPIO Pin 3, 3rd bit, defined as High + * ... + * + * @param pin + */ + void set_gpio_high(int pin); + + /** + * @brief Modify GPCLR0 (GPIO Pin Output Clear 0) register to set pin as low + * Writing zero to this register has no effect, please use Linux::GPIO_RPI_BCM::set_gpio_high + * to set pin as high. + * + * GPCLR0 is a 32bits register that each bit points to a respective GPIO pin: + * 0b...101 + * ││└── GPIO Pin 1, 1st bit, LSBit, defined as Low + * │└─── GPIO Pin 2, 2nd bit, No effect + * └──── GPIO Pin 3, 3rd bit, defined as Low + * + * @param pin + */ + void set_gpio_low(int pin); + + /** + * @brief Read GPLEV0 (GPIO Pin Level 0) register check the logic state of a specific pin + * + * GPLEV0 is a 32bits register that each bit points to a respective GPIO pin: + * 0b...101 + * ││└── GPIO Pin 1, 1st bit, LSBit, Pin is in High state + * │└─── GPIO Pin 2, 2nd bit, Pin is in Low state + * └──── GPIO Pin 3, 3rd bit, Pin is in High state + * + * @param pin + * @return true + * @return false + */ + bool get_gpio_logic_state(int pin); + + // Memory pointer to gpio registers + volatile uint32_t* _gpio; + // Memory range for the gpio registers + static const uint8_t _gpio_registers_memory_range; + // Path to memory device (E.g: /dev/mem) + static const char* _system_memory_device_path; + // File descriptor for the memory device file + // If it's negative, then there was an error opening the file. + int _system_memory_device; + // store GPIO output status. + uint32_t _gpio_output_port_status = 0x00; + +}; + +} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_HAL.h b/libraries/AP_HAL_Linux/GPIO_RPI_HAL.h new file mode 100644 index 0000000000000..7cec066a94340 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_HAL.h @@ -0,0 +1,13 @@ +#pragma once + +class GPIO_RPI_HAL { +public: + GPIO_RPI_HAL() {} + virtual void init() = 0; + virtual void pinMode(uint8_t pin, uint8_t output) = 0; + virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) {}; + + virtual uint8_t read(uint8_t pin) = 0; + virtual void write(uint8_t pin, uint8_t value) = 0; + virtual void toggle(uint8_t pin) = 0; +}; diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_RP1.cpp b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.cpp new file mode 100644 index 0000000000000..bef2897ba430d --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.cpp @@ -0,0 +1,178 @@ +#include + +#include "GPIO_RPI_RP1.h" + +#include +#include +#include +#include +#include +#include +#include + +using namespace Linux; + +using namespace AP_HAL; + +GPIO_RPI_RP1::GPIO_RPI_RP1() { +} + +bool GPIO_RPI_RP1::openMemoryDevice() { + _system_memory_device = open(PATH_DEV_GPIOMEM, O_RDWR | O_SYNC | O_CLOEXEC); + if (_system_memory_device < 0) { + AP_HAL::panic("Can't open %s", PATH_DEV_GPIOMEM); + return false; + } + return true; +} + +void GPIO_RPI_RP1::closeMemoryDevice() { + close(_system_memory_device); + _system_memory_device = -1; +} + +volatile uint32_t* GPIO_RPI_RP1::get_memory_pointer(uint32_t address, uint32_t length) const { + auto pointer = mmap( + nullptr, + length, + PROT_READ | PROT_WRITE | PROT_EXEC, + MAP_SHARED | MAP_LOCKED, // Shared with other processes + _system_memory_device, // File to map + address // Offset to GPIO peripheral + ); + + if (pointer == MAP_FAILED) { + return nullptr; + } + + return static_cast(pointer); +} + +void GPIO_RPI_RP1::init() { + if (!openMemoryDevice()) { + AP_HAL::panic("Failed to initialize memory device."); + return; + } + + _gpio = get_memory_pointer(IO_BANK0_OFFSET, MEM_SIZE); + if (!_gpio) { + AP_HAL::panic("Failed to get GPIO memory map."); + } + + closeMemoryDevice(); +} + +uint32_t GPIO_RPI_RP1::read_register(uint32_t offset) const { + return _gpio[offset]; +} + +void GPIO_RPI_RP1::write_register(uint32_t offset, uint32_t value) { + _gpio[offset] = value; +} + +GPIO_RPI_RP1::Mode GPIO_RPI_RP1::direction(uint8_t pin) const { + uint32_t offset = (SYS_RIO0_OFFSET + RIO_OE) / REG_SIZE; + uint32_t value = (read_register(offset) >> pin) & 0b1; + return value > 0 ? Mode::Output : Mode::Input; +} + +void GPIO_RPI_RP1::set_direction(uint8_t pin, Mode mode) { + uint32_t offset = (SYS_RIO0_OFFSET + RIO_OE) / REG_SIZE; + offset += (mode == Mode::Output ? SET_OFFSET : CLR_OFFSET) / REG_SIZE; + write_register(offset, 1 << pin); +} + +void GPIO_RPI_RP1::input_enable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + SET_OFFSET) / REG_SIZE; + write_register(offset, PADS_IN_ENABLE_MASK); +} + +void GPIO_RPI_RP1::input_disable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + CLR_OFFSET) / REG_SIZE; + write_register(offset, PADS_IN_ENABLE_MASK); +} + +void GPIO_RPI_RP1::output_enable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + CLR_OFFSET) / REG_SIZE; + write_register(offset, PADS_OUT_DISABLE_MASK); +} + +void GPIO_RPI_RP1::output_disable(uint8_t pin) { + uint32_t offset = (PADS_BANK0_OFFSET + PADS_GPIO + pin * PADS_OFFSET + SET_OFFSET) / REG_SIZE; + write_register(offset, PADS_OUT_DISABLE_MASK); +} + +void GPIO_RPI_RP1::pinMode(uint8_t pin, uint8_t mode) { + if (mode == HAL_GPIO_INPUT) { + input_enable(pin); + set_direction(pin, Mode::Input); + set_mode(pin, Mode::Input); + } else if (mode == HAL_GPIO_OUTPUT) { + output_enable(pin); + set_direction(pin, Mode::Output); + set_mode(pin, Mode::Input); + } +} + +void GPIO_RPI_RP1::pinMode(uint8_t pin, uint8_t mode, uint8_t alt) { + if (mode == HAL_GPIO_ALT) { + set_mode(pin, static_cast(alt)); + return; + } + pinMode(pin, mode); +} + +void GPIO_RPI_RP1::set_mode(uint8_t pin, Mode mode) { + FunctionSelect alt_value; + + switch (mode) { + // ALT5 is used for GPIO, check datasheet pinout alternative functions + case Mode::Alt5: + case Mode::Input: + case Mode::Output: + alt_value = FunctionSelect::Alt5; + break; + case Mode::Alt0: alt_value = FunctionSelect::Alt0; break; + case Mode::Alt1: alt_value = FunctionSelect::Alt1; break; + case Mode::Alt2: alt_value = FunctionSelect::Alt2; break; + case Mode::Alt3: alt_value = FunctionSelect::Alt3; break; + case Mode::Alt4: alt_value = FunctionSelect::Alt4; break; + case Mode::Alt6: alt_value = FunctionSelect::Alt6; break; + case Mode::Alt7: alt_value = FunctionSelect::Alt7; break; + case Mode::Alt8: alt_value = FunctionSelect::Alt8; break; + default: alt_value = FunctionSelect::Null; break; + } + + uint32_t ctrl_offset = (IO_BANK0_OFFSET + GPIO_CTRL + (pin * GPIO_OFFSET) + RW_OFFSET) / REG_SIZE; + uint32_t reg_val = read_register(ctrl_offset); + reg_val &= ~CTRL_FUNCSEL_MASK; // Clear existing function select bits + reg_val |= (static_cast(alt_value) << CTRL_FUNCSEL_LSB); + write_register(ctrl_offset, reg_val); + +} + +void GPIO_RPI_RP1::set_pull(uint8_t pin, PadsPull mode) { + uint32_t pads_offset = (PADS_BANK0_OFFSET + PADS_GPIO + (pin * PADS_OFFSET) + RW_OFFSET) / REG_SIZE; + uint32_t reg_val = read_register(pads_offset); + reg_val &= ~PADS_PULL_MASK; // Clear existing bias bits + reg_val |= (static_cast(mode) << PADS_PULL_LSB); + write_register(pads_offset, reg_val); +} + +uint8_t GPIO_RPI_RP1::read(uint8_t pin) { + uint32_t in_offset = (SYS_RIO0_OFFSET + RIO_IN) / REG_SIZE; + uint32_t reg_val = read_register(in_offset); + return (reg_val >> pin) & 0x1; +} + +void GPIO_RPI_RP1::write(uint8_t pin, uint8_t value) { + uint32_t register_offset = value ? SET_OFFSET : CLR_OFFSET; + uint32_t offset = (SYS_RIO0_OFFSET + RIO_OUT + register_offset) / REG_SIZE; + write_register(offset, 1 << pin); +} + +void GPIO_RPI_RP1::toggle(uint8_t pin) { + uint32_t flag = (1 << pin); + _gpio_output_port_status ^= flag; + write(pin, (_gpio_output_port_status & flag) >> pin); +} diff --git a/libraries/AP_HAL_Linux/GPIO_RPI_RP1.h b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.h new file mode 100644 index 0000000000000..8ea1f342fd4c1 --- /dev/null +++ b/libraries/AP_HAL_Linux/GPIO_RPI_RP1.h @@ -0,0 +1,169 @@ +#pragma once + +#include +#include "GPIO_RPI_HAL.h" + +namespace Linux { + +/** + * @brief Class for Raspberry PI 5 GPIO control + * + * For more information: + * - RP1 datasheet: https://datasheets.raspberrypi.com/rp1/rp1-peripherals.pdf + * - gpiomem0: https://github.com/raspberrypi/linux/blob/1e53604087930e7cf42eee3d42572d0d6f54c86a/arch/arm/boot/dts/broadcom/bcm2712-rpi.dtsi#L178 + * - Address: 0x400d'0000, Size: 0x3'0000 + * + */ +class GPIO_RPI_RP1 : public GPIO_RPI_HAL { +public: + GPIO_RPI_RP1(); + void init() override; + void pinMode(uint8_t pin, uint8_t mode) override; + void pinMode(uint8_t pin, uint8_t mode, uint8_t alt) override; + + uint8_t read(uint8_t pin) override; + void write(uint8_t pin, uint8_t value) override; + void toggle(uint8_t pin) override; + + enum class PadsPull : uint8_t { + Off = 0, + Down = 1, + Up = 2, + }; + + void set_pull(uint8_t pin, PadsPull mode); + +private: + // gpiomem0 already maps the 0x400d'0000 address for us + static constexpr const char* PATH_DEV_GPIOMEM = "/dev/gpiomem0"; + static constexpr uint32_t MEM_SIZE = 0x30000; + static constexpr uint32_t REG_SIZE = sizeof(uint32_t); + + // Register offsets from RP1 datasheet 'Table 2. Peripheral Address Map' + // E.g: + // - IO_BANK0_OFFSET: 0x0'0000 result in 0x400d'0000 + // - SYS_RIO0_OFFSET: 0x1'0000 result in 0x400e'0000 + // ... + static constexpr uint32_t IO_BANK0_OFFSET = 0x00000; + static constexpr uint32_t SYS_RIO0_OFFSET = 0x10000; + static constexpr uint32_t PADS_BANK0_OFFSET = 0x20000; + + // GPIO control from https://github.com/raspberrypi/linux/blob/21012295fe87a7ccc1c356d1e268fd289aafbad1/drivers/pinctrl/pinctrl-rp1.c + static constexpr uint32_t RIO_OUT = 0x00; + static constexpr uint32_t RIO_OE = 0x04; + static constexpr uint32_t RIO_IN = 0x08; + + // GPIO control from '2.4. Atomic register access' + static constexpr uint32_t RW_OFFSET = 0x0000; + static constexpr uint32_t XOR_OFFSET = 0x1000; + static constexpr uint32_t SET_OFFSET = 0x2000; + static constexpr uint32_t CLR_OFFSET = 0x3000; + + static constexpr uint32_t GPIO_CTRL = 0x0004; + static constexpr uint32_t GPIO_OFFSET = 8; + + static constexpr uint32_t PADS_GPIO = 0x04; + static constexpr uint32_t PADS_OFFSET = 4; + + /** + * GPIO control from 'Table 8. GPI0_CTRL, GPI1_CTRL, ...' + * + * 0b0000'0000'0000'0000'0000'0000'0001'1101 + * ├┘│├─┘├┘├─┘├┘├─┘├┘├─┘├┘│ ├──────┘└────┴─ Bits 4:0 FUNCSEL: Function select + * │ ││ │ │ │ │ │ │ │ │ └────────────── Bits 11:5 F_M: Filter/debounce time constant M + * │ ││ │ │ │ │ │ │ │ └──────────────── Bits 13:12 OUTOVER: Output control + * │ ││ │ │ │ │ │ │ └────────────────── Bits 15:14 OEOVER: Output enable control + * │ ││ │ │ │ │ │ └───────────────────── Bits 17:16 INOVER: Input control + * │ ││ │ │ │ │ └─────────────────────── Bits 19:18 Reserved + * │ ││ │ │ │ └────────────────────────── Bits 20:21 IRQMASK_EDGE_LOW/HIGH + * │ ││ │ │ └──────────────────────────── Bits 22:23 IRQMASK_LEVEL_LOW/HIGH + * │ ││ │ └─────────────────────────────── Bits 24:25 IRQMASK_F_EDGE_LOW/HIGH + * │ ││ └───────────────────────────────── Bits 26:27 IRQMASK_DB_LEVEL_LOW/HIGH + * │ │└──────────────────────────────────── Bit 28 IRQRESET: Interrupt edge detector reset + * │ └───────────────────────────────────── Bit 29 Reserved + * └─────────────────────────────────────── Bits 31:30 IRQOVER: Interrupt control + */ + static constexpr uint32_t CTRL_FUNCSEL_MASK = 0x001f; + static constexpr uint32_t CTRL_FUNCSEL_LSB = 0; + static constexpr uint32_t CTRL_OUTOVER_MASK = 0x3000; + static constexpr uint32_t CTRL_OUTOVER_LSB = 12; + static constexpr uint32_t CTRL_OEOVER_MASK = 0xc000; + static constexpr uint32_t CTRL_OEOVER_LSB = 14; + static constexpr uint32_t CTRL_INOVER_MASK = 0x30000; + static constexpr uint32_t CTRL_INOVER_LSB = 16; + static constexpr uint32_t CTRL_IRQOVER_MASK = 0xc0000000; + static constexpr uint32_t CTRL_IRQOVER_LSB = 30; + + /** + * Mask for PADS_BANK control from 'Table 21.' + * + * 0b0...001'1101 + * ├──┘││├─┘││└─ Bit 1 SLEWFAST: Slew rate control. 1 = Fast, 0 = Slow + * │ │││ │└── Bit 2 SCHMITT: Enable schmitt trigger + * │ │││ └─── Bit 3 PDE: Pull down enable + * │ ││└────── Bits 4:5 DRIVE: Drive strength + * │ │└─────── Bit 6 IE: Input enable + * │ └──────── Bit 7 OD: Output disable. Has priority over output enable from + * └──────────── Bits 31:8 Reserved + */ + static constexpr uint32_t PADS_IN_ENABLE_MASK = 0x40; + static constexpr uint32_t PADS_OUT_DISABLE_MASK = 0x80; + static constexpr uint32_t PADS_PULL_MASK = 0x0c; + static constexpr uint32_t PADS_PULL_LSB = 2; + + enum class FunctionSelect : uint8_t { + Alt0 = 0, + Alt1 = 1, + Alt2 = 2, + Alt3 = 3, + Alt4 = 4, + Alt5 = 5, + Alt6 = 6, + Alt7 = 7, + Alt8 = 8, + Null = 31 + }; + + enum Mode { + Input, + Output, + Alt0, + Alt1, + Alt2, + Alt3, + Alt4, + Alt5, + Alt6, + Alt7, + Alt8, + Null + }; + + enum Bias { + Off, + PullDown, + PullUp + }; + + volatile uint32_t* _gpio; + int _system_memory_device; + uint32_t _gpio_output_port_status = 0; + + bool openMemoryDevice(); + void closeMemoryDevice(); + volatile uint32_t* get_memory_pointer(uint32_t address, uint32_t range) const; + + uint32_t read_register(uint32_t offset) const; + void write_register(uint32_t offset, uint32_t value); + + Mode direction(uint8_t pin) const; + void set_direction(uint8_t pin, Mode mode); + void input_enable(uint8_t pin); + void input_disable(uint8_t pin); + void output_enable(uint8_t pin); + void output_disable(uint8_t pin); + + void set_mode(uint8_t pin, Mode mode); +}; + +} diff --git a/libraries/AP_HAL_Linux/RCInput.cpp b/libraries/AP_HAL_Linux/RCInput.cpp index b4e933d096450..09bfd63c7de11 100644 --- a/libraries/AP_HAL_Linux/RCInput.cpp +++ b/libraries/AP_HAL_Linux/RCInput.cpp @@ -330,229 +330,3 @@ void RCInput::_update_periods(uint16_t *periods, uint8_t len) _num_channels = len; rc_input_count++; } - - -/* - add some bytes of input in DSM serial stream format, coping with partial packets - */ -bool RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes) -{ - if (nbytes == 0) { - return false; - } - const uint8_t dsm_frame_size = sizeof(dsm.frame); - bool ret = false; - - uint32_t now = AP_HAL::millis(); - if (now - dsm.last_input_ms > 5) { - // resync based on time - dsm.partial_frame_count = 0; - } - dsm.last_input_ms = now; - - while (nbytes > 0) { - size_t n = nbytes; - if (dsm.partial_frame_count + n > dsm_frame_size) { - n = dsm_frame_size - dsm.partial_frame_count; - } - if (n > 0) { - memcpy(&dsm.frame[dsm.partial_frame_count], bytes, n); - dsm.partial_frame_count += n; - nbytes -= n; - bytes += n; - } - - if (dsm.partial_frame_count == dsm_frame_size) { - dsm.partial_frame_count = 0; - uint16_t values[16] {}; - uint16_t num_values=0; - /* - we only accept input when nbytes==0 as dsm is highly - sensitive to framing, and extra bytes may be an - indication this is really SRXL - */ - if (dsm_decode(AP_HAL::micros64(), dsm.frame, values, &num_values, 16) && - num_values >= MIN_NUM_CHANNELS && - nbytes == 0) { - for (uint8_t i=0; i _num_channels) { - _num_channels = num_values; - } - rc_input_count++; -#if 0 - printf("Decoded DSM %u channels %u %u %u %u %u %u %u %u\n", - (unsigned)num_values, - values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7]); -#endif - ret = true; - } - } - } - return ret; -} - - -/* - add some bytes of input in SUMD serial stream format, coping with partial packets - */ -bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes) -{ - uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS]; - uint8_t rssi; - uint8_t rx_count; - uint16_t channel_count; - bool ret = false; - - while (nbytes > 0) { - if (sumd_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) { - if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) { - continue; - } - for (uint8_t i=0; i 0) { - if (st24_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) { - if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) { - continue; - } - for (uint8_t i=0; i 0) { - if (srxl_decode(now, *bytes++, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS, &failsafe_state) == 0) { - if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) { - continue; - } - for (uint8_t i=0; i 5) { - // resync based on time - sbus.partial_frame_count = 0; - } - sbus.last_input_ms = now; - - while (nbytes > 0) { - size_t n = nbytes; - if (sbus.partial_frame_count + n > sbus_frame_size) { - n = sbus_frame_size - sbus.partial_frame_count; - } - if (n > 0) { - memcpy(&sbus.frame[sbus.partial_frame_count], bytes, n); - sbus.partial_frame_count += n; - nbytes -= n; - bytes += n; - } - - if (sbus.partial_frame_count == sbus_frame_size) { - sbus.partial_frame_count = 0; - uint16_t values[16] {}; - uint16_t num_values=0; - bool sbus_failsafe; - if (AP_RCProtocol_SBUS::sbus_decode(sbus.frame, values, &num_values, sbus_failsafe, 16) && - num_values >= MIN_NUM_CHANNELS) { - for (uint8_t i=0; i _num_channels) { - _num_channels = num_values; - } - if (!sbus_failsafe) { - rc_input_count++; - } -#if 0 - printf("Decoded SBUS %u channels %u %u %u %u %u %u %u %u %s\n", - (unsigned)num_values, - values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7], - sbus_failsafe?"FAIL":"OK"); -#endif - } - } - } -} diff --git a/libraries/AP_HAL_Linux/RCInput.h b/libraries/AP_HAL_Linux/RCInput.h index a639cb4533b1b..ef7022d50caf6 100644 --- a/libraries/AP_HAL_Linux/RCInput.h +++ b/libraries/AP_HAL_Linux/RCInput.h @@ -33,21 +33,6 @@ class RCInput : public AP_HAL::RCInput { // specific implementations virtual void _timer_tick() {} - // add some DSM input bytes, for RCInput over a serial port - bool add_dsm_input(const uint8_t *bytes, size_t nbytes); - - // add some SBUS input bytes, for RCInput over a serial port - void add_sbus_input(const uint8_t *bytes, size_t nbytes); - - // add some SUMD input bytes, for RCInput over a serial port - bool add_sumd_input(const uint8_t *bytes, size_t nbytes); - - // add some st24 input bytes, for RCInput over a serial port - bool add_st24_input(const uint8_t *bytes, size_t nbytes); - - // add some srxl input bytes, for RCInput over a serial port - bool add_srxl_input(const uint8_t *bytes, size_t nbytes); - protected: void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1); void _update_periods(uint16_t *periods, uint8_t len); @@ -81,20 +66,6 @@ class RCInput : public AP_HAL::RCInput { uint16_t bit_ofs; } dsm_state; - // state of add_dsm_input - struct { - uint8_t frame[16]; - uint8_t partial_frame_count; - uint32_t last_input_ms; - } dsm; - - // state of add_sbus_input - struct { - uint8_t frame[25]; - uint8_t partial_frame_count; - uint32_t last_input_ms; - } sbus; - int16_t _rssi = -1; }; diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp index e6a266b564135..476ab6655a578 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp @@ -69,14 +69,17 @@ void SPIUARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) * it's sage to update speed */ _dev->set_speed(AP_HAL::Device::SPEED_HIGH); + high_speed_set = true; debug("Set higher SPI-frequency"); } else { _dev->set_speed(AP_HAL::Device::SPEED_LOW); + high_speed_set = false; debug("Set lower SPI-frequency"); } break; default: _dev->set_speed(AP_HAL::Device::SPEED_LOW); + high_speed_set = false; debug("Set lower SPI-frequency"); debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b); break; diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.h b/libraries/AP_HAL_Linux/SPIUARTDriver.h index 05be43b9ecce0..07e451d243bc4 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.h +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.h @@ -11,6 +11,9 @@ class SPIUARTDriver : public UARTDriver { SPIUARTDriver(); void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; void _timer_tick(void) override; + uint32_t get_baud_rate() const override { + return high_speed_set ? 4000000U : 1000000U; + } protected: int _write_fd(const uint8_t *buf, uint16_t n) override; @@ -23,6 +26,8 @@ class SPIUARTDriver : public UARTDriver { uint32_t _last_update_timestamp; bool _external; + + bool high_speed_set; }; } diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index ec47114cc6ee3..02a1afba7b88e 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -56,7 +56,7 @@ class UARTDriver : public AP_HAL::UARTDriver { uint32_t bw_in_bytes_per_second() const override; - uint32_t get_baud_rate() const override { return _baudrate; } + virtual uint32_t get_baud_rate() const override { return _baudrate; } private: AP_HAL::OwnPtr _device; diff --git a/libraries/AP_HAL_Linux/Util_RPI.cpp b/libraries/AP_HAL_Linux/Util_RPI.cpp index 9f464374d7c19..f39606675e77f 100644 --- a/libraries/AP_HAL_Linux/Util_RPI.cpp +++ b/libraries/AP_HAL_Linux/Util_RPI.cpp @@ -62,25 +62,29 @@ void UtilRPI::_get_board_type_using_peripheral_base() _linux_board_version = LINUX_BOARD_TYPE::UNKNOWN_BOARD; printf("Cannot detect board-type \r\n"); break; + case 0x10: + _linux_board_version = LINUX_BOARD_TYPE::RPI_5; + printf("RPI 5 \r\n"); + break; case 0x20000000: _linux_board_version = LINUX_BOARD_TYPE::RPI_ZERO_1; printf("RPI Zero / 1 \r\n"); - printf("Peripheral base address is %x\n", base); break; case 0x3f000000: _linux_board_version = LINUX_BOARD_TYPE::RPI_2_3_ZERO2; printf("RPI 2, 3 or Zero-2 \r\n"); - printf("Peripheral base address is %x\n", base); break; case 0xfe000000: _linux_board_version = LINUX_BOARD_TYPE::RPI_4; printf("RPI 4 \r\n"); - printf("Peripheral base address is %x\n", base); break; case 0x40000000: _linux_board_version = LINUX_BOARD_TYPE::ALLWINNWER_H616; printf("AllWinner-H616 \r\n"); break; + default: + printf("Unknown board \n\r"); + printf("Peripheral base address is %x\n", base); } return ; diff --git a/libraries/AP_HAL_Linux/Util_RPI.h b/libraries/AP_HAL_Linux/Util_RPI.h index 67a6fc8ead44f..4aa3427dca88f 100644 --- a/libraries/AP_HAL_Linux/Util_RPI.h +++ b/libraries/AP_HAL_Linux/Util_RPI.h @@ -8,6 +8,7 @@ enum class LINUX_BOARD_TYPE: int { RPI_ZERO_1=0, RPI_2_3_ZERO2=1, RPI_4=2, + RPI_5=3, ALLWINNWER_H616=100, UNKNOWN_BOARD=999 }; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index de94ee65900be..52f67237ac2be 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal; using namespace HALSITL; #define streq(a, b) (!strcmp(a, b)) -SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const char *arg) +SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const char *arg, const uint8_t portNumber) { if (streq(name, "benewake_tf02")) { if (benewake_tf02 != nullptr) { @@ -314,6 +314,14 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const } gps[x-1] = new SITL::GPS(x-1); return gps[x-1]; + } else if (streq(name, "ELRS")) { + // Only allocate if not done already + // MAVLink serial ports have begin called several times + if (elrs == nullptr) { + elrs = new SITL::ELRS(portNumber, this); + _sitl->set_stop_MAVLink_sim_state(); + } + return elrs; } AP_HAL::panic("unknown simulated device: %s", name); @@ -481,6 +489,10 @@ void SITL_State_Common::sim_update(void) gps[i]->update(); } } + + if (elrs != nullptr) { + elrs->update(); + } } /* diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 19e7356c3b605..de3d75d657ac4 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -53,6 +53,8 @@ #include #include +#include + #include "AP_HAL_SITL.h" #include "AP_HAL_SITL_Namespace.h" #include "HAL_SITL_Class.h" @@ -88,7 +90,7 @@ class HALSITL::SITL_State_Common { // create a simulated serial device; type of device is given by // name parameter - SITL::SerialDevice *create_serial_sim(const char *name, const char *arg); + SITL::SerialDevice *create_serial_sim(const char *name, const char *arg, const uint8_t portNumber); // simulated airspeed, sonar and battery monitor float sonar_pin_voltage; // pin 0 @@ -231,6 +233,9 @@ class HALSITL::SITL_State_Common { // simulated GPS devices SITL::GPS *gps[2]; // constrained by # of parameter sets + // Simulated ELRS radio + SITL::ELRS *elrs; + // returns a voltage between 0V to 5V which should appear as the // voltage from the sensor float _sonar_pin_voltage() const; diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 1f8d3935df8d4..ea253d314b989 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -14,6 +14,7 @@ #include #include #include +#include #include #include #include @@ -38,6 +39,8 @@ #include #include #include +#include + #include #include @@ -142,6 +145,7 @@ static const struct { { "djix", MultiCopter::create }, { "cwx", MultiCopter::create }, { "hexa", MultiCopter::create }, + { "hexax", MultiCopter::create }, { "hexa-cwx", MultiCopter::create }, { "hexa-dji", MultiCopter::create }, { "octa", MultiCopter::create }, @@ -170,6 +174,7 @@ static const struct { { "last_letter", last_letter::create }, { "tracker", Tracker::create }, { "balloon", Balloon::create }, + { "glider", Glider::create }, { "plane", Plane::create }, { "calibration", Calibration::create }, { "vectored", Submarine::create }, @@ -183,6 +188,9 @@ static const struct { { "JSON", JSON::create }, { "blimp", Blimp::create }, { "novehicle", NoVehicle::create }, +#if AP_SIM_STRATOBLIMP_ENABLED + { "stratoblimp", StratoBlimp::create }, +#endif }; void SITL_State::_set_signal_handlers(void) const diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index cb645d11f625e..8a9600ca4d6c1 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -77,11 +77,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) if (strcmp(path, "GPS1") == 0) { /* gps */ _connected = true; - _sim_serial_device = _sitlState->create_serial_sim("gps:1", ""); + _sim_serial_device = _sitlState->create_serial_sim("gps:1", "", _portNumber); } else if (strcmp(path, "GPS2") == 0) { /* 2nd gps */ _connected = true; - _sim_serial_device = _sitlState->create_serial_sim("gps:2", ""); + _sim_serial_device = _sitlState->create_serial_sim("gps:2", "", _portNumber); } else { /* parse type:args:flags string for path. For example: @@ -109,7 +109,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) // add sanity check here that we're doing mavlink on this port? ::printf("SIM-ADSB connection on SERIAL%u\n", _portNumber); _connected = true; - _sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr); + _sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr, _portNumber); } else #endif if (strcmp(devtype, "tcp") == 0) { @@ -132,7 +132,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) if (!_connected) { ::printf("SIM connection %s:%s on SERIAL%u\n", args1, args2, _portNumber); _connected = true; - _sim_serial_device = _sitlState->create_serial_sim(args1, args2); + _sim_serial_device = _sitlState->create_serial_sim(args1, args2, _portNumber); } } else if (strcmp(devtype, "udpclient") == 0) { // udp client connection @@ -815,13 +815,11 @@ void UARTDriver::handle_writing_from_writebuffer_to_device() SITL::SIM *_sitl = AP::sitl(); if (_sitl && _sitl->telem_baudlimit_enable) { // limit byte rate to configured baudrate - uint32_t now = AP_HAL::micros(); - float dt = 1.0e-6 * (now - last_write_tick_us); - max_bytes = _uart_baudrate * dt / 10; + // Byte rate is bit rate divided by 10. 8 bits of data + start/stop bits + max_bytes = baud_limits.write.max_bytes(float(_uart_baudrate) * 0.1); if (max_bytes == 0) { return; } - last_write_tick_us = now; } #endif if (_packetise) { @@ -884,13 +882,11 @@ void UARTDriver::handle_reading_from_device_to_readbuffer() SITL::SIM *_sitl = AP::sitl(); if (_sitl && _sitl->telem_baudlimit_enable) { // limit byte rate to configured baudrate - uint32_t now = AP_HAL::micros(); - float dt = 1.0e-6 * (now - last_read_tick_us); - max_bytes = _uart_baudrate * dt / 10; + // Byte rate is bit rate divided by 10. 8 bits of data + start/stop bits + max_bytes = baud_limits.read.max_bytes(float(_uart_baudrate) * 0.1); if (max_bytes == 0) { return; } - last_read_tick_us = now; } #endif diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 88803c9ddbe40..11a272d7524ef 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -9,6 +9,7 @@ #include #include #include +#include #include @@ -113,8 +114,10 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { uint16_t _mc_myport; // for baud-rate limiting: - uint32_t last_read_tick_us; - uint32_t last_write_tick_us; + struct { + DataRateLimit write; + DataRateLimit read; + } baud_limits; HAL_Semaphore write_mtx; diff --git a/libraries/AP_HAL_SITL/sitl_airspeed.cpp b/libraries/AP_HAL_SITL/sitl_airspeed.cpp index 2c149c1916a7b..cf3e666aa1656 100644 --- a/libraries/AP_HAL_SITL/sitl_airspeed.cpp +++ b/libraries/AP_HAL_SITL/sitl_airspeed.cpp @@ -24,27 +24,6 @@ using namespace HALSITL; #define VOLTS_TO_PASCAL 819 #define PASCAL_TO_VOLTS(_p) (_p/VOLTS_TO_PASCAL) -// return current scale factor that converts from equivalent to true airspeed -// valid for altitudes up to 10km AMSL -// assumes standard atmosphere lapse rate -static float get_EAS2TAS(float altitude) -{ - float pressure = AP::baro().get_pressure(); - if (is_zero(pressure)) { - return 1.0f; - } - - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(altitude * 0.001, sigma, delta, theta); - - float tempK = C_TO_KELVIN(25) - ISA_LAPSE_RATE * altitude; - const float eas2tas_squared = SSL_AIR_DENSITY / (pressure / (ISA_GAS_CONSTANT * tempK)); - if (!is_positive(eas2tas_squared)) { - return 1.0; - } - return sqrtf(eas2tas_squared); -} - /* convert airspeed in m/s to an airspeed sensor value */ @@ -52,7 +31,7 @@ void SITL_State::_update_airspeed(float true_airspeed) { for (uint8_t i=0; iairspeed[i]; - float airspeed = true_airspeed / get_EAS2TAS(_sitl->state.altitude); + float airspeed = true_airspeed / AP_Baro::get_EAS2TAS_for_alt_amsl(_sitl->state.altitude); const float diff_pressure = sq(airspeed) / arspd.ratio; float airspeed_raw; diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index fefa91ebf0377..47b75e8d5e667 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -346,7 +346,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; } } @@ -372,7 +372,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()) { @@ -453,7 +453,11 @@ void AP_IOMCU::read_telem() TelemetryData t { .temperature_cdeg = int16_t(telem->temperature_cdeg[i]), .voltage = float(telem->voltage_cvolts[i]) * 0.01, - .current = float(telem->current_camps[i]) * 0.01 + .current = float(telem->current_camps[i]) * 0.01, +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + .edt2_status = telem->edt2_status[i], + .edt2_stress = telem->edt2_stress[i], +#endif }; update_telem_data(esc_group * 4 + i, t, telem->types[i]); } @@ -791,7 +795,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) { @@ -1112,7 +1116,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= IOMCU_MAX_TELEM_CHANNELS) { continue; } - dshot_telem[i].error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); + dshot_i.error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); #if HAL_WITH_ESC_TELEM const volatile AP_ESC_Telem_Backend::TelemetryData& telem = esc_telem.get_telem_data(esc_id); // if data is stale then set to zero to avoid phantom data appearing in mavlink if (now_ms - telem.last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS) { - dshot_telem[i].voltage_cvolts[j] = 0; - dshot_telem[i].current_camps[j] = 0; - dshot_telem[i].temperature_cdeg[j] = 0; + dshot_i.voltage_cvolts[j] = 0; + dshot_i.current_camps[j] = 0; + dshot_i.temperature_cdeg[j] = 0; +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + dshot_i.edt2_status[j] = 0; + dshot_i.edt2_stress[j] = 0; +#endif continue; } - dshot_telem[i].voltage_cvolts[j] = uint16_t(roundf(telem.voltage * 100)); - dshot_telem[i].current_camps[j] = uint16_t(roundf(telem.current * 100)); - dshot_telem[i].temperature_cdeg[j] = telem.temperature_cdeg; - dshot_telem[i].types[j] = telem.types; + dshot_i.voltage_cvolts[j] = uint16_t(roundf(telem.voltage * 100)); + dshot_i.current_camps[j] = uint16_t(roundf(telem.current * 100)); + dshot_i.temperature_cdeg[j] = telem.temperature_cdeg; +#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED + dshot_i.edt2_status[j] = uint8_t(telem.edt2_status); + dshot_i.edt2_stress[j] = uint8_t(telem.edt2_stress); +#endif + dshot_i.types[j] = telem.types; #endif } } @@ -966,7 +975,7 @@ bool AP_IOMCU_FW::handle_code_write() } /* copy channel data */ uint16_t i = 0, num_values = rx_io_packet.count; - while ((i < IOMCU_MAX_CHANNELS) && (num_values > 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 +1225,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; i 1) { filter[instance].update(num_calculated_notch_frequencies, calculated_notch_freq_hz); } else { diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 9bce50d4ac57d..aa103bb608473 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -449,12 +449,6 @@ class AP_InertialSensor : AP_AccelCal_Client float calculated_notch_freq_hz[INS_MAX_NOTCHES]; uint8_t num_calculated_notch_frequencies; - // Update the harmonic notch frequency - void update_notch_freq_hz(float scaled_freq); - - // Update the harmonic notch frequencies - void update_notch_frequencies_hz(uint8_t num_freqs, const float scaled_freq[]); - // runtime update of notch parameters void update_params(uint8_t instance, bool converging, float gyro_rate); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp index 110d3586b64f1..e815994619415 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensensev3.cpp @@ -468,6 +468,9 @@ static inline float uint20_to_float(uint8_t msb, uint8_t bits, uint8_t lsb) bool AP_InertialSensor_Invensensev3::accumulate_highres_samples(const FIFODataHighRes *data, uint8_t n_samples) { +#if INV3_ENABLE_FIFO_LOGGING + const uint64_t tstart = AP_HAL::micros64(); +#endif for (uint8_t i = 0; i < n_samples; i++) { const FIFODataHighRes &d = data[i]; @@ -488,6 +491,9 @@ bool AP_InertialSensor_Invensensev3::accumulate_highres_samples(const FIFODataHi accel *= accel_scale; gyro *= gyro_scale; +#if INV3_ENABLE_FIFO_LOGGING + Write_GYR(gyro_instance, tstart+(i*backend_period_us), gyro, true); +#endif const float temp = d.temperature * temp_sensitivity + temp_zero; // these four calls are about 40us diff --git a/libraries/AP_JSON/AP_JSON.cpp b/libraries/AP_JSON/AP_JSON.cpp index 823de3512538a..32ee85fe2beef 100644 --- a/libraries/AP_JSON/AP_JSON.cpp +++ b/libraries/AP_JSON/AP_JSON.cpp @@ -72,7 +72,7 @@ AP_JSON::value *AP_JSON::load_json(const char *filename) char *start = strchr(buf, '{'); if (!start) { - ::printf("Invalid json %s", filename); + ::printf("Invalid json %s\n", filename); delete[] buf; return nullptr; } @@ -89,13 +89,13 @@ AP_JSON::value *AP_JSON::load_json(const char *filename) AP_JSON::value *obj = new AP_JSON::value; if (obj == nullptr) { - ::printf("Invalid allocate json for %s", filename); + ::printf("Invalid allocate json for %s\n", filename); delete[] buf; return nullptr; } std::string err = AP_JSON::parse(*obj, start); if (!err.empty()) { - ::printf("parse failed for json %s", filename); + ::printf("parse failed for json %s\n", filename); delete obj; delete[] buf; return nullptr; diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 5ea3d7b595be7..b61db7fc7c9aa 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -6,7 +6,7 @@ #include "AP_Logger_File.h" #include "AP_Logger_Flash_JEDEC.h" -#include "AP_Logger_W25N01GV.h" +#include "AP_Logger_W25NXX.h" #include "AP_Logger_MAVLink.h" #include diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp b/libraries/AP_Logger/AP_Logger_W25NXX.cpp similarity index 68% rename from libraries/AP_Logger/AP_Logger_W25N01GV.cpp rename to libraries/AP_Logger/AP_Logger_W25NXX.cpp index 86ce642c991d5..d10facf8b924a 100644 --- a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp +++ b/libraries/AP_Logger/AP_Logger_W25NXX.cpp @@ -5,7 +5,7 @@ #include -#include "AP_Logger_W25N01GV.h" +#include "AP_Logger_W25NXX.h" #if HAL_LOGGING_DATAFLASH_ENABLED @@ -30,37 +30,40 @@ extern const AP_HAL::HAL& hal; #define JEDEC_STATUS_BUSY 0x01 #define JEDEC_STATUS_WRITEPROTECT 0x02 -#define W25N01G_STATUS_REG 0xC0 -#define W25N01G_PROT_REG 0xA0 -#define W25N01G_CONF_REG 0xB0 -#define W25N01G_STATUS_EFAIL 0x04 -#define W25N01G_STATUS_PFAIL 0x08 - -#define W25N01G_PROT_SRP1_ENABLE (1 << 0) -#define W25N01G_PROT_WP_E_ENABLE (1 << 1) -#define W25N01G_PROT_TB_ENABLE (1 << 2) -#define W25N01G_PROT_PB0_ENABLE (1 << 3) -#define W25N01G_PROT_PB1_ENABLE (1 << 4) -#define W25N01G_PROT_PB2_ENABLE (1 << 5) -#define W25N01G_PROT_PB3_ENABLE (1 << 6) -#define W25N01G_PROT_SRP2_ENABLE (1 << 7) - -#define W25N01G_CONFIG_ECC_ENABLE (1 << 4) -#define W25N01G_CONFIG_BUFFER_READ_MODE (1 << 3) - -#define W25N01G_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled) -#define W25N01G_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us -#define W25N01G_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms -#define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms +#define W25NXX_STATUS_REG 0xC0 +#define W25NXX_PROT_REG 0xA0 +#define W25NXX_CONF_REG 0xB0 +#define W25NXX_STATUS_EFAIL 0x04 +#define W25NXX_STATUS_PFAIL 0x08 + +#define W25NXX_PROT_SRP1_ENABLE (1 << 0) +#define W25NXX_PROT_WP_E_ENABLE (1 << 1) +#define W25NXX_PROT_TB_ENABLE (1 << 2) +#define W25NXX_PROT_PB0_ENABLE (1 << 3) +#define W25NXX_PROT_PB1_ENABLE (1 << 4) +#define W25NXX_PROT_PB2_ENABLE (1 << 5) +#define W25NXX_PROT_PB3_ENABLE (1 << 6) +#define W25NXX_PROT_SRP2_ENABLE (1 << 7) + +#define W25NXX_CONFIG_ECC_ENABLE (1 << 4) +#define W25NXX_CONFIG_BUFFER_READ_MODE (1 << 3) + +#define W25NXX_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled) +#define W25NXX_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us +#define W25NXX_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms +#define W25NXX_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms + #define W25N01G_NUM_BLOCKS 1024 +#define W25N02K_NUM_BLOCKS 2048 #define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21 +#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22 -void AP_Logger_W25N01GV::Init() +void AP_Logger_W25NXX::Init() { dev = hal.spi->get_device("dataflash"); if (!dev) { - AP_HAL::panic("PANIC: AP_Logger W25N01GV device not found"); + AP_HAL::panic("PANIC: AP_Logger W25NXX device not found"); return; } @@ -80,17 +83,17 @@ void AP_Logger_W25N01GV::Init() uint8_t b = JEDEC_DEVICE_RESET; dev->transfer(&b, 1, nullptr, 0); } - hal.scheduler->delay(W25N01G_TIMEOUT_RESET_MS); + hal.scheduler->delay(W25NXX_TIMEOUT_RESET_MS); // disable write protection - WriteStatusReg(W25N01G_PROT_REG, 0); + WriteStatusReg(W25NXX_PROT_REG, 0); // enable ECC and buffer mode - WriteStatusReg(W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE); + WriteStatusReg(W25NXX_CONF_REG, W25NXX_CONFIG_ECC_ENABLE|W25NXX_CONFIG_BUFFER_READ_MODE); - printf("W25N01GV status: SR-1=0x%x, SR-2=0x%x, SR-3=0x%x\n", - ReadStatusRegBits(W25N01G_PROT_REG), - ReadStatusRegBits(W25N01G_CONF_REG), - ReadStatusRegBits(W25N01G_STATUS_REG)); + printf("W25NXX status: SR-1=0x%x, SR-2=0x%x, SR-3=0x%x\n", + ReadStatusRegBits(W25NXX_PROT_REG), + ReadStatusRegBits(W25NXX_CONF_REG), + ReadStatusRegBits(W25NXX_STATUS_REG)); AP_Logger_Block::Init(); } @@ -98,7 +101,7 @@ void AP_Logger_W25N01GV::Init() /* wait for busy flag to be cleared */ -void AP_Logger_W25N01GV::WaitReady() +void AP_Logger_W25NXX::WaitReady() { if (flash_died) { return; @@ -115,7 +118,7 @@ void AP_Logger_W25N01GV::WaitReady() } } -bool AP_Logger_W25N01GV::getSectorCount(void) +bool AP_Logger_W25NXX::getSectorCount(void) { WaitReady(); @@ -133,6 +136,13 @@ bool AP_Logger_W25N01GV::getSectorCount(void) df_PageSize = 2048; df_PagePerBlock = 64; df_PagePerSector = 64; // make sectors equivalent to block + flash_blockNum = W25N01G_NUM_BLOCKS; + break; + case JEDEC_ID_WINBOND_W25N02KV: + df_PageSize = 2048; + df_PagePerBlock = 64; + df_PagePerSector = 64; // make sectors equivalent to block + flash_blockNum = W25N02K_NUM_BLOCKS; break; default: @@ -141,14 +151,14 @@ bool AP_Logger_W25N01GV::getSectorCount(void) return false; } - df_NumPages = W25N01G_NUM_BLOCKS * df_PagePerBlock; + df_NumPages = flash_blockNum * df_PagePerBlock; printf("SPI Flash 0x%08x found pages=%u\n", id, df_NumPages); return true; } // Read the status register bits -uint8_t AP_Logger_W25N01GV::ReadStatusRegBits(uint8_t bits) +uint8_t AP_Logger_W25NXX::ReadStatusRegBits(uint8_t bits) { WITH_SEMAPHORE(dev_sem); uint8_t cmd[2] { JEDEC_READ_STATUS, bits }; @@ -157,7 +167,7 @@ uint8_t AP_Logger_W25N01GV::ReadStatusRegBits(uint8_t bits) return status; } -void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits) +void AP_Logger_W25NXX::WriteStatusReg(uint8_t reg, uint8_t bits) { WaitReady(); WITH_SEMAPHORE(dev_sem); @@ -165,14 +175,14 @@ void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits) dev->transfer(cmd, 3, nullptr, 0); } -bool AP_Logger_W25N01GV::Busy() +bool AP_Logger_W25NXX::Busy() { - uint8_t status = ReadStatusRegBits(W25N01G_STATUS_REG); + uint8_t status = ReadStatusRegBits(W25NXX_STATUS_REG); - if ((status & W25N01G_STATUS_PFAIL) != 0) { + if ((status & W25NXX_STATUS_PFAIL) != 0) { printf("Program failure!\n"); } - if ((status & W25N01G_STATUS_EFAIL) != 0) { + if ((status & W25NXX_STATUS_EFAIL) != 0) { printf("Erase failure!\n"); } @@ -182,18 +192,18 @@ bool AP_Logger_W25N01GV::Busy() /* send a command with an address */ -void AP_Logger_W25N01GV::send_command_addr(uint8_t command, uint32_t PageAdr) +void AP_Logger_W25NXX::send_command_addr(uint8_t command, uint32_t PageAdr) { uint8_t cmd[4]; cmd[0] = command; - cmd[1] = 0; // dummy + cmd[1] = (PageAdr >> 16) & 0xff; cmd[2] = (PageAdr >> 8) & 0xff; cmd[3] = (PageAdr >> 0) & 0xff; dev->transfer(cmd, 4, nullptr, 0); } -void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum) +void AP_Logger_W25NXX::PageToBuffer(uint32_t pageNum) { if (pageNum == 0 || pageNum > df_NumPages+1) { printf("Invalid page read %u\n", pageNum); @@ -237,7 +247,7 @@ void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum) } } -void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum) +void AP_Logger_W25NXX::BufferToPage(uint32_t pageNum) { if (pageNum == 0 || pageNum > df_NumPages+1) { printf("Invalid page write %u\n", pageNum); @@ -278,7 +288,7 @@ void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum) /* erase one sector (sizes varies with hw) */ -void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum) +void AP_Logger_W25NXX::SectorErase(uint32_t blockNum) { WriteEnable(); WITH_SEMAPHORE(dev_sem); @@ -290,12 +300,12 @@ void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum) /* erase one 4k sector */ -void AP_Logger_W25N01GV::Sector4kErase(uint32_t sectorNum) +void AP_Logger_W25NXX::Sector4kErase(uint32_t sectorNum) { SectorErase(sectorNum); } -void AP_Logger_W25N01GV::StartErase() +void AP_Logger_W25NXX::StartErase() { WriteEnable(); @@ -309,10 +319,10 @@ void AP_Logger_W25N01GV::StartErase() printf("Dataflash: erase started\n"); } -bool AP_Logger_W25N01GV::InErase() +bool AP_Logger_W25NXX::InErase() { if (erase_start_ms && !Busy()) { - if (erase_block < W25N01G_NUM_BLOCKS) { + if (erase_block < flash_blockNum) { SectorErase(erase_block++); } else { printf("Dataflash: erase done (%u ms)\n", AP_HAL::millis() - erase_start_ms); @@ -323,7 +333,7 @@ bool AP_Logger_W25N01GV::InErase() return erase_start_ms != 0; } -void AP_Logger_W25N01GV::WriteEnable(void) +void AP_Logger_W25NXX::WriteEnable(void) { WaitReady(); WITH_SEMAPHORE(dev_sem); diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.h b/libraries/AP_Logger/AP_Logger_W25NXX.h similarity index 87% rename from libraries/AP_Logger/AP_Logger_W25N01GV.h rename to libraries/AP_Logger/AP_Logger_W25NXX.h index 556603eaffd22..885800e913648 100644 --- a/libraries/AP_Logger/AP_Logger_W25N01GV.h +++ b/libraries/AP_Logger/AP_Logger_W25NXX.h @@ -9,13 +9,13 @@ #if HAL_LOGGING_DATAFLASH_ENABLED -class AP_Logger_W25N01GV : public AP_Logger_Block { +class AP_Logger_W25NXX : public AP_Logger_Block { public: - AP_Logger_W25N01GV(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : + AP_Logger_W25NXX(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : AP_Logger_Block(front, writer) {} static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { - return new AP_Logger_W25N01GV(front, ls); + return new AP_Logger_W25NXX(front, ls); } void Init(void) override; bool CardInserted() const override { return !flash_died && df_NumPages > 0; } @@ -39,6 +39,8 @@ class AP_Logger_W25N01GV : public AP_Logger_Block { AP_HAL::OwnPtr dev; AP_HAL::Semaphore *dev_sem; + uint32_t flash_blockNum; + bool flash_died; uint32_t erase_start_ms; uint16_t erase_block; diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 4f9f07ad1c239..8a60c3b68bea9 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -261,6 +261,7 @@ void AP_Mission::reset() _flags.do_cmd_loaded = false; _flags.do_cmd_all_done = false; _flags.in_landing_sequence = false; + _flags.in_return_path = false; _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE; _do_cmd.index = AP_MISSION_CMD_INDEX_NONE; _prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE; @@ -398,11 +399,18 @@ bool AP_Mission::verify_command(const Mission_Command& cmd) bool AP_Mission::start_command(const Mission_Command& cmd) { - // check for landing related commands and set in_landing_sequence flag + // check for landing related commands and set flags if (is_landing_type_cmd(cmd.id) || cmd.id == MAV_CMD_DO_LAND_START) { - set_in_landing_sequence_flag(true); + _flags.in_landing_sequence = true; + + } else if (cmd.id == MAV_CMD_DO_RETURN_PATH_START) { + _flags.in_return_path = true; + } else if (is_takeoff_type_cmd(cmd.id)) { - set_in_landing_sequence_flag(false); + // Clear landing and return path flags on takeoff + _flags.in_landing_sequence = false; + _flags.in_return_path = false; + } if (cmd.id == MAV_CMD_DO_JUMP || cmd.id == MAV_CMD_JUMP_TAG || cmd.id == MAV_CMD_DO_JUMP_TAG) { @@ -550,10 +558,20 @@ int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle) // set_current_cmd - jumps to command specified by index bool AP_Mission::set_current_cmd(uint16_t index) { - // read command to check for DO_LAND_START + // Clear flags + _flags.in_landing_sequence = false; + _flags.in_return_path = false; + + // read command to check for DO_LAND_START and DO_RETURN_PATH_START Mission_Command cmd; - if (!read_cmd_from_storage(index, cmd) || (cmd.id != MAV_CMD_DO_LAND_START)) { - _flags.in_landing_sequence = false; + if (read_cmd_from_storage(index, cmd)) { + if (cmd.id == MAV_CMD_DO_LAND_START) { + _flags.in_landing_sequence = true; + + } else if (cmd.id == MAV_CMD_DO_RETURN_PATH_START) { + _flags.in_return_path = true; + + } } // mission command has been set, don't track history. @@ -853,6 +871,7 @@ bool AP_Mission::stored_in_location(uint16_t id) case MAV_CMD_NAV_SPLINE_WAYPOINT: case MAV_CMD_NAV_GUIDED_ENABLE: case MAV_CMD_DO_SET_HOME: + case MAV_CMD_DO_RETURN_PATH_START: case MAV_CMD_DO_LAND_START: case MAV_CMD_DO_GO_AROUND: case MAV_CMD_DO_SET_ROI: @@ -1169,6 +1188,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ cmd.content.repeat_servo.cycle_time = packet.param4; // time in seconds break; + case MAV_CMD_DO_RETURN_PATH_START: // MAV ID: 188 case MAV_CMD_DO_LAND_START: // MAV ID: 189 break; @@ -1681,6 +1701,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c packet.param4 = cmd.content.repeat_servo.cycle_time; // time in milliseconds converted to seconds break; + case MAV_CMD_DO_RETURN_PATH_START: // MAV ID: 188 case MAV_CMD_DO_LAND_START: // MAV ID: 189 break; @@ -1940,6 +1961,7 @@ void AP_Mission::complete() // flag mission as complete _flags.state = MISSION_COMPLETE; _flags.in_landing_sequence = false; + _flags.in_return_path = false; // callback to main program's mission complete function _mission_complete_fn(); @@ -2131,24 +2153,18 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i jump_index = cmd_index; } - // check if jump command is 'repeat forever' - if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) { + // get number of times jump command has already been run + if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER || + get_jump_times_run(temp_cmd) < temp_cmd.content.jump.num_times) { + // update the record of the number of times run + if (increment_jump_num_times_if_found && !_flags.resuming_mission) { + increment_jump_times_run(temp_cmd, send_gcs_msg); + } // continue searching from jump target cmd_index = temp_cmd.content.jump.target; } else { - // get number of times jump command has already been run - int16_t jump_times_run = get_jump_times_run(temp_cmd); - if (jump_times_run < temp_cmd.content.jump.num_times) { - // update the record of the number of times run - if (increment_jump_num_times_if_found && !_flags.resuming_mission) { - increment_jump_times_run(temp_cmd, send_gcs_msg); - } - // continue searching from jump target - cmd_index = temp_cmd.content.jump.target; - } else { - // jump has been run specified number of times so move search to next command in mission - cmd_index++; - } + // jump has been run specified number of times so move search to next command in mission + cmd_index++; } } else { // this is a non-jump command so return it @@ -2284,7 +2300,11 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd, bool send_gcs_ms if (_jump_tracking[i].index == cmd.index) { _jump_tracking[i].num_times_run++; if (send_gcs_msg) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times); + if (cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/unlimited", _jump_tracking[i].index, _jump_tracking[i].num_times_run); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times); + } } return; } else if (_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) { @@ -2319,7 +2339,6 @@ void AP_Mission::check_eeprom_version() // be found. uint16_t AP_Mission::get_landing_sequence_start(const Location ¤t_loc) { - const Location::AltFrame current_loc_alt_frame = current_loc.get_alt_frame(); uint16_t landing_start_index = 0; float min_distance = -1; @@ -2339,15 +2358,7 @@ uint16_t AP_Mission::get_landing_sequence_start(const Location ¤t_loc) continue; } - float tmp_distance; - if (current_loc_alt_frame == tmp.content.location.get_alt_frame() || tmp.content.location.change_alt_frame(current_loc_alt_frame)) { - // 3D distance - altitudes are able to be compared in the same frame - tmp_distance = tmp.content.location.get_distance_NED(current_loc).length(); - } else { - // 2D distance - no altitude - tmp_distance = tmp.content.location.get_distance(current_loc); - } - + const float tmp_distance = tmp.content.location.get_distance_NED_alt_frame(current_loc).length(); if (min_distance < 0 || tmp_distance < min_distance) { min_distance = tmp_distance; landing_start_index = i; @@ -2374,7 +2385,6 @@ bool AP_Mission::jump_to_landing_sequence(const Location ¤t_loc) } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing sequence start"); - _flags.in_landing_sequence = true; return true; } @@ -2382,6 +2392,55 @@ bool AP_Mission::jump_to_landing_sequence(const Location ¤t_loc) return false; } +/* + find the closest point on the mission after a DO_RETURN_PATH_START and before DO_LAND_START or landing + */ +bool AP_Mission::jump_to_closest_mission_leg(const Location ¤t_loc) +{ + if (_flags.state == MISSION_RUNNING) { + // if mission is already running don't switch away from a active landing or return path + if (_flags.in_landing_sequence) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing sequence active"); + return true; + + } else if (_flags.in_return_path) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Return path active"); + return true; + } + } + + uint16_t landing_start_index = 0; + float min_distance = -1; + + // Go through mission and check each DO_RETURN_PATH_START + for (uint16_t i = 1; i < num_commands(); i++) { + Mission_Command tmp; + if (read_cmd_from_storage(i, tmp) && (tmp.id == MAV_CMD_DO_RETURN_PATH_START)) { + uint16_t tmp_index; + float tmp_distance; + if (distance_to_mission_leg(i, tmp_distance, tmp_index, current_loc) && (min_distance < 0 || tmp_distance <= min_distance)){ + min_distance = tmp_distance; + landing_start_index = tmp_index; + } + } + } + + if (landing_start_index != 0 && set_current_cmd(landing_start_index)) { + + // if the mission has ended it has to be restarted + if (state() == AP_Mission::MISSION_STOPPED) { + resume(); + } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Return path started"); + _flags.in_return_path = true; + return true; + } + + // Failed to find do land start + return false; +} + // jumps the mission to the closest landing abort that is planned, returns false if unable to find a valid abort bool AP_Mission::jump_to_abort_landing_sequence(const Location ¤t_loc) { @@ -2413,8 +2472,6 @@ bool AP_Mission::jump_to_abort_landing_sequence(const Location ¤t_loc) resume(); } - _flags.in_landing_sequence = false; - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing abort sequence start"); return true; } @@ -2533,6 +2590,90 @@ bool AP_Mission::distance_to_landing(uint16_t index, float &tot_distance, Locati return ret; } +// Approximate the distance travelled to return to the mission path. DO_JUMP commands are observed in look forward. +// Stop searching once reaching a landing or do-land-start +bool AP_Mission::distance_to_mission_leg(uint16_t start_index, float &rejoin_distance, uint16_t &rejoin_index, const Location& current_loc) +{ + Location prev_loc; + Mission_Command temp_cmd; + rejoin_distance = -1; + rejoin_index = -1; + bool ret = false; + + // back up jump tracking to reset after distance calculation + jump_tracking_struct _jump_tracking_backup[AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS]; + for (uint8_t i=0; i get_critical_speed(); } + bool rotor_speed_above_critical(void) const { return get_rotor_speed() >= get_critical_speed(); } // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index a996fb7d04cf0..33cc445904aca 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -691,3 +691,14 @@ bool AP_MotorsHeli_Single::use_tail_RSC() const return (type == TAIL_TYPE::DIRECTDRIVE_VARPITCH) || (type == TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV); } + +#if HAL_LOGGING_ENABLED +void AP_MotorsHeli_Single::Log_Write(void) +{ + // For single heli we have to apply an additional cyclic scaler of sqrt(2.0) because the + // definition of when we achieve _cyclic_max is different to dual heli. In single, _cyclic_max + // is limited at sqrt(2.0), in dual it is limited at 1.0 + float cyclic_angle_scaler = get_cyclic_angle_scaler() * sqrtf(2.0); + _swashplate.write_log(cyclic_angle_scaler, _collective_min_deg.get(), _collective_max_deg.get(), _collective_min.get(), _collective_max.get()); +} +#endif diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 61e6588a5ab9f..72754a11342ce 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -33,7 +33,7 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { AP_MotorsHeli_Single(uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) : AP_MotorsHeli(speed_hz), _tail_rotor(SRV_Channel::k_heli_tail_rsc, AP_MOTORS_HELI_SINGLE_TAILRSC), - _swashplate(AP_MOTORS_MOT_1, AP_MOTORS_MOT_2, AP_MOTORS_MOT_3, AP_MOTORS_MOT_5) + _swashplate(AP_MOTORS_MOT_1, AP_MOTORS_MOT_2, AP_MOTORS_MOT_3, AP_MOTORS_MOT_5, 1U) { AP_Param::setup_object_defaults(this, var_info); }; @@ -77,6 +77,11 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // Thrust Linearization handling Thrust_Linearization thr_lin {*this}; +#if HAL_LOGGING_ENABLED + // Blade angle logging - called at 10 Hz + void Log_Write(void) override; +#endif + // var_info static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp index 3471edc168cc9..5a93212739d91 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp @@ -87,13 +87,10 @@ const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = { AP_GROUPEND }; -AP_MotorsHeli_Swash::AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3) +AP_MotorsHeli_Swash::AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t instance) : + _instance(instance), + _motor_num{mot_0, mot_1, mot_2, mot_3} { - _motor_num[0] = mot_0; - _motor_num[1] = mot_1; - _motor_num[2] = mot_2; - _motor_num[3] = mot_3; - AP_Param::setup_object_defaults(this, var_info); } @@ -219,6 +216,11 @@ void AP_MotorsHeli_Swash::calculate(float roll, float pitch, float collective) collective = 1 - collective; } + // Store inputs for logging + _roll_input = roll; + _pitch_input = pitch; + _collective_input_scaled = collective; + for (uint8_t i = 0; i < _max_num_servos; i++) { if (!_enabled[i]) { // This servo is not enabled @@ -283,3 +285,37 @@ uint32_t AP_MotorsHeli_Swash::get_output_mask() const } return mask; } + +#if HAL_LOGGING_ENABLED +// Write SWSH log for this instance of swashplate +void AP_MotorsHeli_Swash::write_log(float cyclic_scaler, float col_ang_min, float col_ang_max, int16_t col_min, int16_t col_max) const +{ + // Calculate the collective contribution to blade pitch angle + // Swashplate receives the scaled collective value based on the col_min and col_max params. We have to reverse the scaling here to do the angle calculation. + float collective_scalar = ((float)(col_max-col_min))*1e-3; + collective_scalar = MAX(collective_scalar, 1e-3); + float _collective_input = (_collective_input_scaled - (float)(col_min - 1000)*1e-3) / collective_scalar; + float col = (col_ang_max - col_ang_min) * _collective_input + col_ang_min; + + // Calculate the cyclic contribution to blade pitch angle + float tcyc = norm(_roll_input, _pitch_input) * cyclic_scaler; + float pcyc = _pitch_input * cyclic_scaler; + float rcyc = _roll_input * cyclic_scaler; + + // @LoggerMessage: SWSH + // @Description: Helicopter swashplate logging + // @Field: TimeUS: Time since system startup + // @Field: I: Swashplate instance + // @Field: Col: Blade pitch angle contribution from collective + // @Field: TCyc: Total blade pitch angle contribution from cyclic + // @Field: PCyc: Blade pitch angle contribution from pitch cyclic + // @Field: RCyc: Blade pitch angle contribution from roll cyclic + AP::logger().WriteStreaming("SWSH", "TimeUS,I,Col,TCyc,PCyc,RCyc", "s#dddd", "F-0000", "QBffff", + AP_HAL::micros64(), + _instance, + col, + tcyc, + pcyc, + rcyc); +} +#endif diff --git a/libraries/AP_Motors/AP_MotorsHeli_Swash.h b/libraries/AP_Motors/AP_MotorsHeli_Swash.h index 927777e98372e..a1c84b21a2130 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Swash.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Swash.h @@ -5,6 +5,7 @@ #include #include // ArduPilot Mega Vector/Matrix math Library #include +#include // swashplate types enum SwashPlateType { @@ -19,7 +20,7 @@ enum SwashPlateType { class AP_MotorsHeli_Swash { public: - AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3); + AP_MotorsHeli_Swash(uint8_t mot_0, uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t instance); // configure - configure the swashplate settings for any updated parameters void configure(); @@ -39,6 +40,11 @@ class AP_MotorsHeli_Swash { // Get function output mask uint32_t get_output_mask() const; +#if HAL_LOGGING_ENABLED + // Write SWSH log for this instance of swashplate + void write_log(float cyclic_scaler, float col_ang_min, float col_ang_max, int16_t col_min, int16_t col_max) const; +#endif + // var_info static const struct AP_Param::GroupInfo var_info[]; @@ -75,7 +81,13 @@ class AP_MotorsHeli_Swash { float _pitchFactor[_max_num_servos]; // Pitch axis scaling of servo output based on servo position float _collectiveFactor[_max_num_servos]; // Collective axis scaling of servo output based on servo position float _output[_max_num_servos]; // Servo output value - uint8_t _motor_num[_max_num_servos]; // Motor function to use for output + const uint8_t _motor_num[_max_num_servos]; // Motor function to use for output + const uint8_t _instance; // Swashplate instance. Used for logging. + + // Variables stored for logging + float _roll_input; + float _pitch_input; + float _collective_input_scaled; // parameters AP_Int8 _swashplate_type; // Swash Type Setting diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 5d315b9176908..11630bb775496 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -86,7 +86,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @Param: PWM_TYPE // @DisplayName: Output PWM type - // @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output + // @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output.PWMRange and PWMAngle are PWM special/rare cases for ESCs that dont calibrate normally (some Sub motors) or where each ESC must have its PWM range set individually using the Servo params instead of PWM_MIN/MAX parameters. // @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200,8:PWMRange,9:PWMAngle // @User: Advanced // @RebootRequired: True diff --git a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp index ff2114864a455..437cb4b560d72 100644 --- a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp +++ b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp @@ -3,6 +3,7 @@ #include "AP_Motors_Class.h" #include #include +#include #include #define AP_MOTORS_BATT_VOLT_FILT_HZ 0.5 // battery voltage filtered at 0.5hz @@ -193,7 +194,7 @@ float Thrust_Linearization::get_compensation_gain() const #if AP_MOTORS_DENSITY_COMP == 1 // air density ratio is increasing in density / decreasing in altitude - const float air_density_ratio = AP::baro().get_air_density_ratio(); + const float air_density_ratio = AP::ahrs().get_air_density_ratio(); if (air_density_ratio > 0.3 && air_density_ratio < 1.5) { ret *= 1.0 / constrain_float(air_density_ratio, 0.5, 1.25); } 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 7d02dcec6f5bd..e8b635e560fed 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp @@ -158,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; } @@ -221,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])) { @@ -245,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 { @@ -262,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) { @@ -283,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)) { @@ -319,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; } @@ -362,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); @@ -397,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 @@ -409,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; } @@ -1573,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.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index d689ab85919d7..af10084e6cc2d 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -863,7 +863,7 @@ void NavEKF3_core::calcOutputStates() if (!accelPosOffset.is_zero()) { // calculate the average angular rate across the last IMU update // note delAngDT is prevented from being zero in readIMUData() - Vector3F angRate = imuDataNew.delAng * (1.0f/imuDataNew.delAngDT); + Vector3F angRate = dal.ins().get_gyro(gyro_index_active).toftype(); // Calculate the velocity of the body frame origin relative to the IMU in body frame // and rotate into earth frame. Note % operator has been overloaded to perform a cross product diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index e1903a7faf724..2b5138062ffae 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -886,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 ff4bd0a00b2c3..d25e801778ef6 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2099,7 +2099,7 @@ void AP_Param::convert_toplevel_objects(const TopLevelObjectConversion conversio 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 @@ -2143,10 +2143,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 589fd09fabfed..1be4a820d1c89 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -495,11 +495,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 @@ -785,6 +791,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_RCMapper/AP_RCMapper.cpp b/libraries/AP_RCMapper/AP_RCMapper.cpp index fc09016e1dfcc..39af6944ae7b8 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.cpp +++ b/libraries/AP_RCMapper/AP_RCMapper.cpp @@ -1,3 +1,7 @@ +#include "AP_RCMapper_config.h" + +#if AP_RCMAPPER_ENABLED + #include #include "AP_RCMapper.h" @@ -75,3 +79,5 @@ RCMapper::RCMapper(void) RCMapper *AP::rcmap() { return RCMapper::get_singleton(); } + +#endif // AP_RCMAPPER_ENABLED diff --git a/libraries/AP_RCMapper/AP_RCMapper_config.h b/libraries/AP_RCMapper/AP_RCMapper_config.h index ad11cb1785b85..021ff08c2579f 100644 --- a/libraries/AP_RCMapper/AP_RCMapper_config.h +++ b/libraries/AP_RCMapper/AP_RCMapper_config.h @@ -1,5 +1,7 @@ #pragma once +#include + #ifndef AP_RCMAPPER_ENABLED #define AP_RCMAPPER_ENABLED 1 #endif diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index b7b6bfdf945da..2202dbd5cc1ad 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -38,6 +38,7 @@ #include "AP_RCProtocol_Joystick_SFML.h" #include "AP_RCProtocol_UDP.h" #include "AP_RCProtocol_FDM.h" +#include "AP_RCProtocol_Radio.h" #include #include @@ -110,7 +111,9 @@ void AP_RCProtocol::init() UDP_backend->set_fdm_backend(FDM_backend); #endif // AP_RCPROTOCOL_UDP_ENABLED #endif // AP_RCPROTOCOL_FDM_ENABLED - +#if AP_RCPROTOCOL_RADIO_ENABLED + backend[AP_RCProtocol::RADIO] = new AP_RCProtocol_Radio(*this); +#endif } AP_RCProtocol::~AP_RCProtocol() @@ -472,6 +475,9 @@ bool AP_RCProtocol::new_input() #endif #if AP_RCPROTOCOL_FDM_ENABLED AP_RCProtocol::FDM, +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + AP_RCProtocol::RADIO, #endif }; for (const auto protocol : pollable) { @@ -620,6 +626,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol) #if AP_RCPROTOCOL_FDM_ENABLED case FDM: return "FDM"; +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + case RADIO: + return "Radio"; #endif case NONE: break; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.h b/libraries/AP_RCProtocol/AP_RCProtocol.h index 6234e0a1a1309..37f46a28da6d1 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol.h @@ -89,6 +89,9 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_FDM_ENABLED FDM = 18, +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + RADIO = 19, #endif NONE //last enum always is None }; @@ -125,6 +128,12 @@ class AP_RCProtocol { _disabled_for_pulses |= (1U<<(uint8_t)protocol); } +// in the case we've disabled most backends then the "return true" in +// the following method can never be reached, and the compiler gets +// annoyed at that. +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wswitch-unreachable" + // for protocols without strong CRCs we require 3 good frames to lock on bool requires_3_frames(enum rcprotocol_t p) { switch (p) { @@ -185,12 +194,16 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_FDM_ENABLED case FDM: +#endif +#if AP_RCPROTOCOL_RADIO_ENABLED + case RADIO: #endif case NONE: return false; } return false; } +#pragma GCC diagnostic pop uint8_t num_channels(); uint16_t read(uint8_t chan); diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Radio.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.cpp new file mode 100644 index 0000000000000..f0f37703f3f00 --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.cpp @@ -0,0 +1,53 @@ +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_RADIO_ENABLED + +#include "AP_RCProtocol_Radio.h" +#include + +void AP_RCProtocol_Radio::update() +{ + auto *radio = AP_Radio::get_singleton(); + if (radio == nullptr) { + return; + } + if (!init_done) { + radio->init(); + init_done = true; + } + + // allow the radio to handle mavlink on the main thread: + radio->update(); + + const uint32_t last_recv_us = radio->last_recv_us(); + if (last_recv_us == last_input_us) { + // no new data + return; + } + last_input_us = last_recv_us; + + const auto num_channels = radio->num_channels(); + uint16_t rcin_values[MAX_RCIN_CHANNELS]; + for (uint8_t i=0; iread(i); + } + + add_input( + num_channels, + rcin_values, + false, // failsafe + 0, // check me + 0 // link quality + ); +} + +void AP_RCProtocol_Radio::start_bind() +{ + auto *radio = AP_Radio::get_singleton(); + if (radio == nullptr) { + return; + } + radio->start_recv_bind(); +} + +#endif // AP_RCPROTOCOL_RADIO_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Radio.h b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.h new file mode 100644 index 0000000000000..0144e0e42697a --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Radio.h @@ -0,0 +1,32 @@ +#pragma once + +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_RADIO_ENABLED + +/* + * Reads fixed-length packets containing either 8 or 16 2-byte values, + * and interprets them as RC input. + */ + +#include "AP_RCProtocol_Backend.h" + +class AP_RCProtocol_Radio : public AP_RCProtocol_Backend { +public: + + using AP_RCProtocol_Backend::AP_RCProtocol_Backend; + + void update() override; + + void start_bind(void) override; + +private: + + bool init(); + bool init_done; + + uint32_t last_input_us; +}; + + +#endif // AP_RCPROTOCOL_RADIO_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_config.h b/libraries/AP_RCProtocol/AP_RCProtocol_config.h index a648b0969bbc9..4cb2b65124611 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_config.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_config.h @@ -3,6 +3,7 @@ #include #include #include +#include #ifndef AP_RCPROTOCOL_ENABLED #define AP_RCPROTOCOL_ENABLED 1 @@ -43,6 +44,10 @@ #define AP_RCPROTOCOL_PPMSUM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_RCPROTOCOL_RADIO_ENABLED +#define AP_RCPROTOCOL_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_RADIO_ENABLED +#endif + #ifndef AP_RCPROTOCOL_SBUS_ENABLED #define AP_RCPROTOCOL_SBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif diff --git a/libraries/AP_ROMFS/AP_ROMFS.cpp b/libraries/AP_ROMFS/AP_ROMFS.cpp index 3a8542e199093..df4e6ad69f848 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.cpp +++ b/libraries/AP_ROMFS/AP_ROMFS.cpp @@ -45,10 +45,9 @@ const AP_ROMFS::embedded_file *AP_ROMFS::find_file(const char *name) } /* - find a compressed file and uncompress it. Space for decompressed data comes - from malloc. Caller must be careful to free the resulting data after use. The - file data buffer is guaranteed to contain at least one null (though it may be - at buf[size]). + Find the named file and return its decompressed data and size. Caller must + call AP_ROMFS::free() on the return value after use to free it. The data is + guaranteed to be null-terminated such that it can be treated as a string. */ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) { @@ -61,20 +60,18 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) size = f->decompressed_size; return f->contents; #else + // add one byte for null termination; ArduPilot's malloc will zero it. uint8_t *decompressed_data = (uint8_t *)malloc(f->decompressed_size+1); if (!decompressed_data) { return nullptr; } if (f->decompressed_size == 0) { - // empty file + // empty file, avoid decompression problems size = 0; return decompressed_data; } - // explicitly null-terminate the data - decompressed_data[f->decompressed_size] = 0; - TINF_DATA *d = (TINF_DATA *)malloc(sizeof(TINF_DATA)); if (!d) { ::free(decompressed_data); @@ -106,7 +103,7 @@ const uint8_t *AP_ROMFS::find_decompress(const char *name, uint32_t &size) #endif } -// free returned data +// free decompressed file data void AP_ROMFS::free(const uint8_t *data) { #ifndef HAL_ROMFS_UNCOMPRESSED diff --git a/libraries/AP_ROMFS/AP_ROMFS.h b/libraries/AP_ROMFS/AP_ROMFS.h index 57efa9f5b8c96..940810dc4172b 100644 --- a/libraries/AP_ROMFS/AP_ROMFS.h +++ b/libraries/AP_ROMFS/AP_ROMFS.h @@ -7,13 +7,13 @@ class AP_ROMFS { public: - // find a file and de-compress, assumning gzip format. The - // decompressed data will be allocated with malloc(). You must - // call AP_ROMFS::free() on the return value after use. The next byte after - // the file data is guaranteed to be null. + // Find the named file and return its decompressed data and size. Caller + // must call AP_ROMFS::free() on the return value after use to free it. + // The data is guaranteed to be null-terminated such that it can be + // treated as a string. static const uint8_t *find_decompress(const char *name, uint32_t &size); - // free returned data + // free decompressed file data static void free(const uint8_t *data); // get the size of a file without decompressing diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index ef0061553eaa7..228e845294c66 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -24,6 +24,7 @@ #include "RPM_Generator.h" #include "RPM_HarmonicNotch.h" #include "RPM_ESC_Telem.h" +#include "RPM_DroneCAN.h" #include @@ -99,6 +100,11 @@ void AP_RPM::init(void) drivers[i] = new AP_RPM_HarmonicNotch(*this, i, state[i]); break; #endif // AP_RPM_HARMONICNOTCH_ENABLED +#if AP_RPM_DRONECAN_ENABLED + case RPM_TYPE_DRONECAN: + drivers[i] = new AP_RPM_DroneCAN(*this, i, state[i]); + break; +#endif // AP_RPM_DRONECAN_ENABLED #if AP_RPM_SIM_ENABLED case RPM_TYPE_SITL: drivers[i] = new AP_RPM_SITL(*this, i, state[i]); @@ -304,6 +310,18 @@ void AP_RPM::Log_RPM() const } #endif +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM +// Return the sensor id to use for streaming over DroneCAN, negative number disables +int8_t AP_RPM::get_dronecan_sensor_id(uint8_t instance) const +{ + if (!enabled(instance)) { + return -1; + } + return _params[instance].dronecan_sensor_id; +} +#endif + + // singleton instance AP_RPM *AP_RPM::_singleton; diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index 6a6b0e4817570..e2643527cf161 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -54,6 +54,9 @@ class AP_RPM #if AP_RPM_GENERATOR_ENABLED RPM_TYPE_GENERATOR = 6, #endif +#if AP_RPM_DRONECAN_ENABLED + RPM_TYPE_DRONECAN = 7, +#endif #if AP_RPM_SIM_ENABLED RPM_TYPE_SITL = 10, #endif @@ -104,6 +107,11 @@ class AP_RPM // check settings are valid bool arming_checks(size_t buflen, char *buffer) const; +#ifdef HAL_PERIPH_ENABLE_RPM_STREAM + // Return the sensor id to use for streaming over DroneCAN, negative number disables + int8_t get_dronecan_sensor_id(uint8_t instance) const; +#endif + private: void convert_params(void); diff --git a/libraries/AP_RPM/AP_RPM_Params.cpp b/libraries/AP_RPM/AP_RPM_Params.cpp index 1d58d41eb693b..dc6f9bb116e41 100644 --- a/libraries/AP_RPM/AP_RPM_Params.cpp +++ b/libraries/AP_RPM/AP_RPM_Params.cpp @@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { // @Param: TYPE // @DisplayName: RPM type // @Description: What type of RPM sensor is connected - // @Values: 0:None,1:Not Used,2:GPIO,3:EFI,4:Harmonic Notch,5:ESC Telemetry Motors Bitmask,6:Generator + // @Values: 0:None,1:Not Used,2:GPIO,3:EFI,4:Harmonic Notch,5:ESC Telemetry Motors Bitmask,6:Generator,7:DroneCAN // @User: Standard AP_GROUPINFO_FLAGS("TYPE", 1, AP_RPM_Params, type, 0, AP_PARAM_FLAG_ENABLE), // Note, 1 was previously for type = PWM. This has been removed from docs to make setup less confusing for users. @@ -78,6 +78,17 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0), #endif +#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM) + // @Param: DC_ID + // @DisplayName: DroneCAN Sensor ID + // @Description: DroneCAN sensor ID to assign to this backend + // @Description{AP_Periph}: DroneCAN sensor ID to send as on AP-Periph -1 disables + // @Range: -1 10 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("DC_ID", 9, AP_RPM_Params, dronecan_sensor_id, -1), +#endif + AP_GROUPEND }; diff --git a/libraries/AP_RPM/AP_RPM_Params.h b/libraries/AP_RPM/AP_RPM_Params.h index 591bd76e7fdaa..5d2f6a7cf925a 100644 --- a/libraries/AP_RPM/AP_RPM_Params.h +++ b/libraries/AP_RPM/AP_RPM_Params.h @@ -33,7 +33,9 @@ class AP_RPM_Params { #if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED AP_Int8 esc_telem_outbound_index; #endif - +#if AP_RPM_DRONECAN_ENABLED || defined(HAL_PERIPH_ENABLE_RPM_STREAM) + AP_Int8 dronecan_sensor_id; +#endif static const struct AP_Param::GroupInfo var_info[]; }; diff --git a/libraries/AP_RPM/AP_RPM_config.h b/libraries/AP_RPM/AP_RPM_config.h index e07aee1b3dd06..03f7868ceface 100644 --- a/libraries/AP_RPM/AP_RPM_config.h +++ b/libraries/AP_RPM/AP_RPM_config.h @@ -46,3 +46,10 @@ #ifndef AP_RPM_ESC_TELEM_OUTBOUND_ENABLED #define AP_RPM_ESC_TELEM_OUTBOUND_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_WITH_ESC_TELEM #endif + +#ifndef AP_RPM_DRONECAN_ENABLED +#define AP_RPM_DRONECAN_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS +#endif +#if AP_RPM_DRONECAN_ENABLED && !HAL_ENABLE_DRONECAN_DRIVERS + #error AP_RPM_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS +#endif diff --git a/libraries/AP_RPM/RPM_DroneCAN.cpp b/libraries/AP_RPM/RPM_DroneCAN.cpp new file mode 100644 index 0000000000000..4657ff7714be6 --- /dev/null +++ b/libraries/AP_RPM/RPM_DroneCAN.cpp @@ -0,0 +1,88 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_RPM_config.h" + +#if AP_RPM_DRONECAN_ENABLED + +#include "RPM_DroneCAN.h" +#include + +AP_RPM_DroneCAN* AP_RPM_DroneCAN::_drivers[]; +uint8_t AP_RPM_DroneCAN::_driver_instance; +HAL_Semaphore AP_RPM_DroneCAN::_driver_sem; + +AP_RPM_DroneCAN::AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) : + AP_RPM_Backend(_ap_rpm, instance, _state) +{ + // Register self in static driver list + WITH_SEMAPHORE(_driver_sem); + _drivers[_driver_instance] = this; + _driver_instance++; +} + +// Subscribe to incoming rpm messages +void AP_RPM_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) +{ + if (ap_dronecan == nullptr) { + return; + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rpm, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("rpm_sub"); + } +} + +// Receive new CAN message +void AP_RPM_DroneCAN::handle_rpm(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_rpm_RPM &msg) +{ + WITH_SEMAPHORE(_driver_sem); + + for (uint8_t i = 0; i < _driver_instance; i++) { + if (_drivers[i] == nullptr) { + continue; + } + // Find params for this instance + const uint8_t instance = _drivers[i]->state.instance; + const AP_RPM_Params& params = _drivers[i]->ap_rpm._params[instance]; + + if (params.dronecan_sensor_id == msg.sensor_id) { + // Driver loaded and looking for this ID, add reading + _drivers[i]->last_reading_ms = AP_HAL::millis(); + _drivers[i]->rpm = msg.rpm * params.scaling; + + const bool heathy = (msg.flags & DRONECAN_SENSORS_RPM_RPM_FLAGS_UNHEALTHY) == 0; + _drivers[i]->signal_quality = heathy ? 0.5 : 0.0; + } + } +} + +void AP_RPM_DroneCAN::update(void) +{ + WITH_SEMAPHORE(_driver_sem); + + // Update state from temporay variables + state.last_reading_ms = last_reading_ms; + state.signal_quality = signal_quality; + state.rate_rpm = rpm; + + // assume we get readings at at least 1Hz, otherwise reset quality to zero + if ((AP_HAL::millis() - state.last_reading_ms) > 1000) { + state.signal_quality = 0; + state.rate_rpm = 0; + } +} + +#endif // AP_RPM_DRONECAN_ENABLED diff --git a/libraries/AP_RPM/RPM_DroneCAN.h b/libraries/AP_RPM/RPM_DroneCAN.h new file mode 100644 index 0000000000000..c9d8e8c0c511a --- /dev/null +++ b/libraries/AP_RPM/RPM_DroneCAN.h @@ -0,0 +1,52 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +#pragma once + +#include "AP_RPM_config.h" + +#if AP_RPM_DRONECAN_ENABLED + +#include "RPM_Backend.h" +#include + +class AP_RPM_DroneCAN : public AP_RPM_Backend +{ +public: + AP_RPM_DroneCAN(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state); + + // Subscribe to incoming rpm messages + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + + // update state + void update(void) override; + +private: + + // Receive new CAN message + static void handle_rpm(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_rpm_RPM &msg); + + // Temporay variables used to update main state in update call + float rpm; + uint32_t last_reading_ms; + float signal_quality; + + // Static list of drivers + static AP_RPM_DroneCAN *_drivers[RPM_MAX_INSTANCES]; + static uint8_t _driver_instance; + static HAL_Semaphore _driver_sem; + +}; + +#endif // AP_RPM_DRONECAN_ENABLED diff --git a/libraries/AP_Radio/AP_Radio_config.h b/libraries/AP_Radio/AP_Radio_config.h index 92ab9fbd789a2..47c53b8c42d98 100644 --- a/libraries/AP_Radio/AP_Radio_config.h +++ b/libraries/AP_Radio/AP_Radio_config.h @@ -3,7 +3,7 @@ #include #ifndef AP_RADIO_ENABLED -#define AP_RADIO_ENABLED HAL_RCINPUT_WITH_AP_RADIO +#define AP_RADIO_ENABLED 0 #endif #ifndef AP_RADIO_BACKEND_DEFAULT_ENABLED 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_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index 62a702bb86b19..f879a1f6e7d01 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -21,6 +21,8 @@ #include "AP_Scheduler_config.h" +#if AP_SCHEDULER_ENABLED + #include "AP_Scheduler.h" #include @@ -539,3 +541,5 @@ AP_Scheduler &scheduler() } }; + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scheduler/AP_Scheduler.h b/libraries/AP_Scheduler/AP_Scheduler.h index 68f39de24a4e7..bf15592d495bc 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.h +++ b/libraries/AP_Scheduler/AP_Scheduler.h @@ -22,6 +22,8 @@ #include "AP_Scheduler_config.h" +#if AP_SCHEDULER_ENABLED + #include #include #include @@ -268,3 +270,5 @@ class AP_Scheduler namespace AP { AP_Scheduler &scheduler(); }; + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scheduler/PerfInfo.cpp b/libraries/AP_Scheduler/PerfInfo.cpp index 1a9db4a96ecd1..6fb2f6dd5dcb9 100644 --- a/libraries/AP_Scheduler/PerfInfo.cpp +++ b/libraries/AP_Scheduler/PerfInfo.cpp @@ -1,3 +1,7 @@ +#include "AP_Scheduler_config.h" + +#if AP_SCHEDULER_ENABLED + #include "PerfInfo.h" #include @@ -217,3 +221,5 @@ void AP::PerfInfo::set_loop_rate(uint16_t rate_hz) filtered_loop_time = 1.0f / rate_hz; } } + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scheduler/PerfInfo.h b/libraries/AP_Scheduler/PerfInfo.h index 83a8e3bdf9414..bbf6052e60ab5 100644 --- a/libraries/AP_Scheduler/PerfInfo.h +++ b/libraries/AP_Scheduler/PerfInfo.h @@ -1,5 +1,9 @@ #pragma once +#include "AP_Scheduler_config.h" + +#if AP_SCHEDULER_ENABLED + #include #include @@ -76,3 +80,5 @@ class PerfInfo { }; }; + +#endif // AP_SCHEDULER_ENABLED diff --git a/libraries/AP_Scripting/applets/copter_terrain_brake.lua b/libraries/AP_Scripting/applets/copter_terrain_brake.lua new file mode 100644 index 0000000000000..dad77c5ff1864 --- /dev/null +++ b/libraries/AP_Scripting/applets/copter_terrain_brake.lua @@ -0,0 +1,130 @@ +--[[ +script to prevent terrain impact in LOITER mode while flying copters in steep terrain +--]] + +local PARAM_TABLE_KEY = 84 +local PARAM_TABLE_PREFIX = "TERR_BRK_" + +local MODE_LOITER = 5 +local MODE_BRAKE = 17 + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 14), 'could not add param table') + +--[[ + // @Param: TERR_BRK_ENABLE + // @DisplayName: terrain brake enable + // @Description: terrain brake enable + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local TERR_BRK_ENABLE = bind_add_param('ENABLE', 1, 1) + +--[[ + // @Param: TERR_BRK_ALT + // @DisplayName: terrain brake altitude + // @Description: terrain brake altitude. The altitude above the ground below which BRAKE mode will be engaged if in LOITER mode. + // @Range: 1 100 + // @Units: m + // @User: Standard +--]] +local TERR_BRK_ALT = bind_add_param('ALT', 2, 30) + +--[[ + // @Param: TERR_BRK_HDIST + // @DisplayName: terrain brake home distance + // @Description: terrain brake home distance. The distance from home where the auto BRAKE will be enabled. When within this distance of home the script will not activate + // @Range: 0 1000 + // @Units: m + // @User: Standard +--]] +local TERR_BRK_HDIST = bind_add_param('HDIST', 3, 100) + +--[[ + // @Param: TERR_BRK_SPD + // @DisplayName: terrain brake speed threshold + // @Description: terrain brake speed threshold. Don't trigger BRAKE if both horizontal speed and descent rate are below this threshold. By setting this to a small value this can be used to allow the user to climb up to a safe altitude in LOITER mode. A value of 0.5 is recommended if you want to use LOITER to recover from an emergency terrain BRAKE mode change. + // @Range: 0 5 + // @Units: m/s + // @User: Standard +--]] +local TERR_BRK_SPD = bind_add_param('SPD', 4, 0) + +local function sq(x) + return x*x +end + +local function run_checks() + if TERR_BRK_ENABLE:get() ~= 1 then + return + end + if not arming:is_armed() then + return + end + if vehicle:get_mode() ~= MODE_LOITER then + return + end + + if not ahrs:home_is_set() then + return + end + local home = ahrs:get_home() + local pos = ahrs:get_location() + if not pos then + return + end + local home_dist = pos:get_distance(home) + if home_dist <= TERR_BRK_HDIST:get() then + return + end + + --[[ + get height above terrain with extrapolation + --]] + local hagl = terrain:height_above_terrain(true) + if hagl >= TERR_BRK_ALT:get() then + return + end + + --[[ + allow for climbing in LOITER mode if enabled + --]] + if TERR_BRK_SPD:get() > 0 then + local spd = ahrs:get_velocity_NED() + if spd ~= nil then + local hspd = math.sqrt(sq(spd:x())+sq(spd:y())) + local drate = spd:z() + if hspd < TERR_BRK_SPD:get() and drate < TERR_BRK_SPD:get() then + return + end + end + end + + if vehicle:set_mode(MODE_BRAKE) then + gcs:send_text(MAV_SEVERITY.EMERGENCY, string.format("Terrain %.1fm - BRAKE", hagl)) + end +end + +--[[ + main update function, called at 1Hz +--]] +function update() + run_checks() + return update, 100 +end + +if TERR_BRK_ENABLE:get() == 1 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("Loaded Loiter/Brake checker")) +end + +-- start running update loop +return update, 1000 + diff --git a/libraries/AP_Scripting/applets/copter_terrain_brake.md b/libraries/AP_Scripting/applets/copter_terrain_brake.md new file mode 100644 index 0000000000000..02edf1d9e8843 --- /dev/null +++ b/libraries/AP_Scripting/applets/copter_terrain_brake.md @@ -0,0 +1,72 @@ +# Copter Loiter Brake + +This script implements an emergency change to BRAKE mode in copter if +you are in LOITER mode and break a terrain altitude limit. The script +is useful when flying in LOITER mode in steep terrain. + +# Parameters + +The script adds the following parameters to control it's behaviour. + +## TERR_BRK_ENABLE + +This must be set to 1 to enable the script. + +## TERR_BRK_ALT + +This is the terrain altitude threshold for engaging BRAKE mode. The +onboard terrain system must be enabled with TERRAIN_ENABLE=1 and +terrain must have either been preloaded to the vehicle (see +https://terrain.ardupilot.org ) or be available from the ground +station over MAVLink. + +Make sure you set sufficient margin to cope with obstacles such as +trees or any local towers or other obstacles. + +## TERR_BRK_HDIST + +This is the distance from home for the BRAKE checking to be +enabled. The default of 100 meters is good for most operations. This +threshold allows you to take over in LOITER mode for low altitude +operations and takeoff/landing when close to home. + +## TERR_BRK_SPD + +This is a speed threshold BRAKE checking to be enabled. If both the +horizontal speed and the descent rate are below this threshold then +BRAKE will not be engaged. This defaults to zero which means no speed +checking is performed. + +You should set this to a small value if you want to be able to recover +from BRAKE mode by climbing straight up in LOITER mode. A value of 0.5 +m/s is recommended. The value needed will be dependent on the amount +of noise there is in your velocity measurement and how gusty the wind +is, but 0.5 should work in most applications. + +If you set this value then to recover in LOITER mode you should raise +the throttle stick to demand climb before you switch back to LOITER +mode. The positive climb rate means BRAKE will not re-engage. + +# Operation + +Install the lua script in the APM/SCRIPTS directory on the flight +controllers microSD card. Review the above parameter descriptions and +decide on the right parameter values for your vehicle and operations. + +Make sure TERRAIN_ENABLE is 1 and you should preload terrain data for +the flight area from https://terrain.ardupilot.org + +It is strongly recommended that you set TERRAIN_SPACING=30 and preload +the SRTM1 terrain data for 30m horizontal resolution of terrain data. + +When the system engages you will see a message like this + "Terrain 29.2m - BRAKE" +where in this example you are 29.2m above the terrain. + +To recover you could use GUIDED mode, or RTL (make sure you have set +RTL_ALT_TYPE to terrain) or if you have set TERR_BRK_SPD to a positive +value then you could raise the throttle stick and switch back to +LOITER mode. + +If the system is continually giving false positives then set +TERR_BRK_ENABLE to zero to disable. diff --git a/libraries/AP_Scripting/applets/revert_param.lua b/libraries/AP_Scripting/applets/revert_param.lua index 27dc9cc943bcf..8ea0498f47e5e 100644 --- a/libraries/AP_Scripting/applets/revert_param.lua +++ b/libraries/AP_Scripting/applets/revert_param.lua @@ -56,6 +56,7 @@ local PSC_prefixes = { "PSC", "Q_P" } local PID_prefixes = { "_RAT_RLL_", "_RAT_PIT_", "_RAT_YAW_" } local PID_suffixes = { "FF", "P", "I", "D", "D_FF", "PDMX", "NEF", "NTF", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" } local angle_axes = { "RLL", "PIT", "YAW" } +local rate_limit_axes = { "R", "P", "Y"} local PSC_types = { "ACCZ", "VELZ", "POSZ", "VELXY", "POSXY" } local OTHER_PARAMS = { "INS_GYRO_FILTER", "INS_ACCEL_FILTER", "PTCH2SRV_TCONST", "RLL2SRV_TCONST" } @@ -89,6 +90,13 @@ for _, atc in ipairs(ATC_prefixes) do end end +-- add angular rate limits +for _, atc in ipairs(ATC_prefixes) do + for _, axis in ipairs(rate_limit_axes) do + add_param(atc .. "_RATE_" .. axis .. "_MAX") + end +end + -- add fixed wing tuning for _, suffix in ipairs(PID_suffixes) do add_param("RLL_RATE_" .. suffix) diff --git a/libraries/AP_Scripting/applets/revert_param.md b/libraries/AP_Scripting/applets/revert_param.md index 63d564db7b490..8b1aafbfdd6f7 100644 --- a/libraries/AP_Scripting/applets/revert_param.md +++ b/libraries/AP_Scripting/applets/revert_param.md @@ -47,6 +47,7 @@ The script covers the following parameters on quadplanes: - Q_A_ANG_RLL_P - Q_A_ANG_PIT_P - Q_A_ANG_YAW_P + - Q_A_RATE_*_MAX - Q_P_ACCZ_* - Q_P_VELZ_* - Q_P_POSZ_* @@ -61,6 +62,7 @@ The script covers the following parameters on copters: - ATC_ANG_RLL_P - ATC_ANG_PIT_P - ATC_ANG_YAW_P + - ATC_RATE_*_MAX - PSC_ACCZ_* - PSC_VELZ_* - PSC_POSZ_* diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 0807c406d1dfc..98732a6b82c6e 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -77,7 +77,7 @@ i2c = {} ---@param address integer -- device address 0 to 128 ---@param clock? uint32_t_ud -- optional bus clock, default 400000 ---@param smbus? boolean -- optional sumbus flag, default false ----@return AP_HAL__I2CDevice_ud +---@return AP_HAL__I2CDevice_ud|nil function i2c:get_device(bus, address, clock, smbus) end -- EFI state structure @@ -337,21 +337,21 @@ function efi:get_state() end -- desc ---@param instance integer ----@return AP_EFI_Backend_ud +---@return AP_EFI_Backend_ud|nil function efi:get_backend(instance) end -- CAN bus interaction ---@class CAN CAN = {} --- get a CAN bus device handler first scripting driver +-- get a CAN bus device handler first scripting driver, will return nil if no driver with protocol Scripting is configured ---@param buffer_len uint32_t_ud -- buffer length 1 to 25 ----@return ScriptingCANBuffer_ud +---@return ScriptingCANBuffer_ud|nil function CAN:get_device(buffer_len) end --- get a CAN bus device handler second scripting driver +-- get a CAN bus device handler second scripting driver, will return nil if no driver with protocol Scripting2 is configured ---@param buffer_len uint32_t_ud -- buffer length 1 to 25 ----@return ScriptingCANBuffer_ud +---@return ScriptingCANBuffer_ud|nil function CAN:get_device2(buffer_len) end -- Auto generated binding @@ -456,8 +456,10 @@ function motor_factor_table_ud:roll(index, value) end ---@class SocketAPM_ud local SocketAPM_ud = {} --- desc -function Socket(param1) end +-- Get a new socket +---@param datagram boolean +---@return SocketAPM_ud +function Socket(datagram) end -- return true if a socket is connected ---@return boolean @@ -494,11 +496,12 @@ function SocketAPM_ud:connect(IP_address, port) end --[[ accept new incoming sockets, returning a new socket. Must be used on a stream socket in listen state --]] -function SocketAPM_ud:accept(param1) end +---@return SocketAPM_ud|nil +function SocketAPM_ud:accept() end -- receive data from a socket ----@param length ----@return data +---@param length integer +---@return string|nil function SocketAPM_ud:recv(length) end -- check for available input @@ -523,6 +526,8 @@ function SocketAPM_ud:close() end this also "closes" the socket and the file from the point of view of lua the underlying socket and file are both closed on end of file --]] +---@param filehandle string +---@return boolean -- success function SocketAPM_ud:sendfile(filehandle) end -- enable SO_REUSEADDR on a socket @@ -1506,7 +1511,7 @@ function ins:gyros_consistent(threshold) end function ins:get_gyro_health(instance) end -- Check if the accelerometers are consistent ----@param threshold float -- the threshold allowed before returning false +---@param threshold number -- the threshold allowed before returning false ---@return boolean function ins:accels_consistent(threshold) end @@ -1553,7 +1558,7 @@ function Motors_dynamic:init(expected_num_motors) end analog = {} -- desc ----@return AP_HAL__AnalogSource_ud +---@return AP_HAL__AnalogSource_ud|nil function analog:channel() end @@ -1696,11 +1701,11 @@ function sub:get_and_clear_button_count(index) end function sub:rangefinder_alt_ok() end -- SURFTRAK mode: return the rangefinder target in cm ----@return float +---@return number function sub:get_rangefinder_target_cm() end -- SURFTRAK mode: set the rangefinder target in cm, return true if successful ----@param new_target_cm float +---@param new_target_cm number ---@return boolean function sub:set_rangefinder_target_cm(new_target_cm) end @@ -1844,7 +1849,7 @@ function mission:get_last_jump_tag() end function mission:jump_to_landing_sequence() end -- Jump to the landing abort sequence --- @return boolean +---@return boolean function mission:jump_to_abort_landing_sequence() end -- desc @@ -1927,7 +1932,7 @@ esc_telem = {} function esc_telem:update_telem_data(instance, telemdata, data_mask) end -- desc ----@param param1 integer +---@param instance integer ---@return uint32_t_ud|nil function esc_telem:get_usage_seconds(instance) end @@ -2024,7 +2029,7 @@ serial = {} -- For instance = 0, returns first such UART, second for instance = 1, and so on. -- If such an instance is not found, returns nil. ---@param instance integer -- the 0-based index of the UART instance to return. ----@return AP_HAL__UARTDriver_ud -- the requested UART instance available for scripting, or nil if none. +---@return AP_HAL__UARTDriver_ud|nil -- the requested UART instance available for scripting, or nil if none. function serial:find_serial(instance) end @@ -2034,7 +2039,7 @@ rc = {} -- desc ---@param chan_num integer ----@return RC_Channel_ud +---@return RC_Channel_ud|nil function rc:get_channel(chan_num) end -- desc @@ -2057,7 +2062,7 @@ function rc:run_aux_function(aux_fun, ch_flag) end -- desc ---@param aux_fun integer ----@return RC_Channel_ud +---@return RC_Channel_ud|nil function rc:find_channel_for_option(aux_fun) end -- desc @@ -2367,10 +2372,12 @@ function vehicle:set_target_throttle_rate_rpy(param1, param2, param3, param4) en function vehicle:nav_script_time_done(param1) end -- desc ----@return integer|nil ----@return integer|nil ----@return number|nil ----@return number|nil +---@return integer|nil -- id +---@return integer|nil -- cmd +---@return number|nil -- arg1 +---@return number|nil -- arg2 +---@return integer|nil -- arg3 +---@return integer|nil -- arg4 function vehicle:nav_script_time() end -- desc @@ -2574,27 +2581,27 @@ local RangeFinder_State_ud = {} function RangeFinder_State() end -- get system time (ms) of last successful update from sensor ----@return number +---@return uint32_t_ud function RangeFinder_State_ud:last_reading() end -- set system time (ms) of last successful update from sensor ----@param value number +---@param value uint32_t_ud function RangeFinder_State_ud:last_reading(value) end -- get sensor status ----@return number +---@return integer function RangeFinder_State_ud:status() end -- set sensor status ----@param value number +---@param value integer function RangeFinder_State_ud:status(value) end -- get number of consecutive valid readings (max out at 10) ----@return number +---@return integer function RangeFinder_State_ud:range_valid_count() end -- set number of consecutive valid readings (max out at 10) ----@param value number +---@param value integer function RangeFinder_State_ud:range_valid_count(value) end -- get distance in meters @@ -2606,19 +2613,19 @@ function RangeFinder_State_ud:distance() end function RangeFinder_State_ud:distance(value) end -- get measurement quality in percent 0-100, -1 -> quality is unknown ----@return number +---@return integer function RangeFinder_State_ud:signal_quality() end -- set measurement quality in percent 0-100, -1 -> quality is unknown ----@param value number +---@param value integer function RangeFinder_State_ud:signal_quality(value) end -- get voltage in millivolts, if applicable, otherwise 0 ----@return number +---@return integer function RangeFinder_State_ud:voltage() end -- set voltage in millivolts, if applicable, otherwise 0 ----@param value number +---@param value integer function RangeFinder_State_ud:voltage(value) end @@ -2662,7 +2669,7 @@ rangefinder = {} -- get backend based on rangefinder instance provided ---@param rangefinder_instance integer ----@return AP_RangeFinder_Backend_ud +---@return AP_RangeFinder_Backend_ud|nil function rangefinder:get_backend(rangefinder_instance) end -- desc @@ -2752,7 +2759,7 @@ proximity = {} -- get backend based on proximity instance provided ---@param instance integer ----@return AP_Proximity_Backend_ud +---@return AP_Proximity_Backend_ud|nil function proximity:get_backend(instance) end -- desc @@ -3322,11 +3329,15 @@ function scripting:restart_all() end -- desc ---@param directoryname string ----@return table -- table of filenames +---@return table|nil -- table of filenames +---@return string|nil -- error string if fails function dirlist(directoryname) end --desc ---@param filename string +---@return boolean|nil -- true on success +---@return nil|string -- error string +---@return integer -- error number function remove(filename) end -- desc @@ -3340,6 +3351,7 @@ function mavlink:init(num_rx_msgid, msg_queue_length) end -- marks mavlink message for receive, message id can be get using mavlink_msgs.get_msgid("MSG_NAME") ---@param msg_id number +---@return boolean -- false if id has been registered already function mavlink:register_rx_msgid(msg_id) end -- receives mavlink message marked for receive using mavlink:register_rx_msgid @@ -3353,10 +3365,12 @@ function mavlink:receive_chan() end ---@param chan integer ---@param msgid integer ---@param message string +---@return boolean -- success function mavlink:send_chan(chan, msgid, message) end -- Block a given MAV_CMD from being procceced by ArduPilot ---@param comand_id integer +---@return boolean function mavlink:block_command(comand_id) end -- Geofence library @@ -3413,8 +3427,8 @@ rtc = {} -- return a time since 1970 in seconds from GMT date elements ---@param year integer -- 20xx ---@param month integer -- 0-11 ----@param day integer -- 1-31 ----@param hour integer -- 0-23 +---@param day integer -- 1-31 +---@param hour integer -- 0-23 ---@param min integer -- 0-60 ---@param sec integer -- 0-60 ---@return uint32_t_ud @@ -3445,10 +3459,11 @@ function fs:stat(param1) end function fs:format() end -- Get the current status of a format. 0=NOT_STARTED, 1=PENDING, 2=IN_PROGRESS, 3=SUCCESS, 4=FAILURE ----@return number +---@return integer function fs:get_format_status() end -- Get crc32 checksum of a file with given name +---@param file_name string ---@return uint32_t_ud|nil function fs:crc32(file_name) end diff --git a/libraries/AP_Scripting/drivers/INF_Inject.lua b/libraries/AP_Scripting/drivers/INF_Inject.lua index 8685ba52a343e..f1296d4946631 100644 --- a/libraries/AP_Scripting/drivers/INF_Inject.lua +++ b/libraries/AP_Scripting/drivers/INF_Inject.lua @@ -34,11 +34,30 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 8), 'could not add p --]] EFI_INF_ENABLE = bind_add_param("ENABLE", 1, 1) +--[[ + // @Param: EFI_INF_OPTIONS + // @DisplayName: EFI INF-Inject options + // @Description: EFI INF driver options + // @Bitmask: 0:EnableLogging + // @User: Standard +--]] +EFI_INF_OPTIONS = bind_add_param("OPTIONS", 2, 0) + +local OPTION_LOGGING = (1<<0) + +--[[ + return true if an option is enabled +--]] +local function option_enabled(option) + return (EFI_INF_OPTIONS:get() & option) ~= 0 +end + if EFI_INF_ENABLE:get() ~= 1 then return end local EFI_FUEL_DENS = bind_param("EFI_FUEL_DENS") +local SCR_VM_I_COUNT = bind_param("SCR_VM_I_COUNT") local uart = serial:find_serial(0) -- first scripting serial if not uart then @@ -53,12 +72,38 @@ if not efi_backend then return end +--[[ + we need a bit more time in this driver +--]] +if SCR_VM_I_COUNT:get() < 50000 then + gcs:send_text(MAV_SEVERITY.INFO, "EFI_INF: raising SCR_VM_I_COUNT to 50000") + SCR_VM_I_COUNT:set_and_save(50000) +end + local state = {} state.last_read_us = uint32_t(0) state.chk0 = 0 state.chk1 = 0 state.total_fuel_g = 0.0 +local file_handle = nil + +--[[ + log a set of bytes +--]] +local function log_bytes(s) + if not file_handle then + file_handle = io.open("INF_Inject.log", "w") + end + if file_handle then + local magic = 0x7fe53b04 + local now_ms = millis():toint() + local hdr = string.pack("= packet_size and not header_ok do + state.chk0 = 0 + state.chk1 = 0 local header0 = string.unpack("name, name); } alias->num_args = atoi(num_args); + + char *num_ret = next_token(); + if (num_ret == NULL) { + error(ERROR_SINGLETON, "Expected number of returns for manual method %s %s", node->name, name); + } + alias->num_ret = atoi(num_ret); } char *depends_keyword = next_token(); @@ -2608,6 +2615,12 @@ void emit_docs_type(struct type type, const char *prefix, const char *suffix) { } } +void emit_docs_return_type(struct type type, int nullable) { + // AP_Objects can be nil + nullable |= (type.type == TYPE_AP_OBJECT); + emit_docs_type(type, "---@return", (nullable == 0) ? "\n" : "|nil\n"); +} + void emit_docs_method(const char *name, const char *method_name, struct method *method) { fprintf(docs, "-- desc\n"); @@ -2632,18 +2645,14 @@ void emit_docs_method(const char *name, const char *method_name, struct method * // return type if ((method->flags & TYPE_FLAGS_NULLABLE) == 0) { - emit_docs_type(method->return_type, "---@return", "\n"); + emit_docs_return_type(method->return_type, FALSE); } arg = method->arguments; // nulable and refences returns while (arg != NULL) { if ((arg->type.type != TYPE_LITERAL) && (arg->type.flags & (TYPE_FLAGS_NULLABLE | TYPE_FLAGS_REFERNCE))) { - if (arg->type.flags & TYPE_FLAGS_NULLABLE) { - emit_docs_type(arg->type, "---@return", "|nil\n"); - } else { - emit_docs_type(arg->type, "---@return", "\n"); - } + emit_docs_return_type(arg->type, arg->type.flags & TYPE_FLAGS_NULLABLE); } arg = arg->next; } @@ -2687,6 +2696,12 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { if (emit_creation) { // creation function + if (node->creation != NULL) { + for (int i = 0; i < node->creation_args; ++i) { + fprintf(docs, "---@param param%i UNKNOWN\n", i+1); + } + } + fprintf(docs, "---@return %s\n", name); fprintf(docs, "function %s(", node->rename ? node->rename : node->sanatized_name); if (node->creation == NULL) { @@ -2768,7 +2783,17 @@ void emit_docs(struct userdata *node, int is_userdata, int emit_creation) { } else if (alias->type == ALIAS_TYPE_MANUAL) { // Cant do a great job, don't know types or return - fprintf(docs, "-- desc\nfunction %s:%s(", name, alias->alias); + fprintf(docs, "-- desc\n"); + + for (int i = 0; i < alias->num_args; ++i) { + fprintf(docs, "---@param param%i UNKNOWN\n", i+1); + } + + for (int i = 0; i < alias->num_ret; ++i) { + fprintf(docs, "---@return UNKNOWN\n"); + } + + fprintf(docs, "function %s:%s(", name, alias->alias); for (int i = 0; i < alias->num_args; ++i) { fprintf(docs, "param%i", i+1); if (i < alias->num_args-1) { @@ -2927,6 +2952,9 @@ int main(int argc, char **argv) { // for set_and_print_new_error_message deprecate warning fprintf(source, "#include \n"); + fprintf(source, "\n"); + // the generated source uses the Scehduler singleton: + fprintf(source, "#include \n"); fprintf(source, "extern const AP_HAL::HAL& hal;\n"); @@ -3053,7 +3081,17 @@ int main(int argc, char **argv) { while(alias) { if (alias->type == ALIAS_TYPE_MANUAL) { // Cant do a great job, don't know types or return - fprintf(docs, "-- desc\nfunction %s(", alias->alias); + fprintf(docs, "-- desc\n"); + + for (int i = 0; i < alias->num_args; ++i) { + fprintf(docs, "---@param param%i UNKNOWN\n", i+1); + } + + for (int i = 0; i < alias->num_ret; ++i) { + fprintf(docs, "---@return UNKNOWN\n"); + } + + fprintf(docs, "function %s(", alias->alias); for (int i = 0; i < alias->num_args; ++i) { fprintf(docs, "param%i", i+1); if (i < alias->num_args-1) { diff --git a/libraries/AP_Scripting/lua/src/ldo.c b/libraries/AP_Scripting/lua/src/ldo.c index c07f4fdb32854..6c627dc3a9fe1 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/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index b1f7baea56152..c8013b813f493 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -682,6 +682,12 @@ int lua_get_CAN_device(lua_State *L) { } } + if (!scripting->_CAN_dev->initialized()) { + // Driver not initialized, probably because there is no can driver set to scripting + // Return nil + return 0; + } + new_ScriptingCANBuffer(L); *((ScriptingCANBuffer**)luaL_checkudata(L, -1, "ScriptingCANBuffer")) = scripting->_CAN_dev->add_buffer(buffer_len); @@ -707,6 +713,12 @@ int lua_get_CAN_device2(lua_State *L) { } } + if (!scripting->_CAN_dev2->initialized()) { + // Driver not initialized, probably because there is no can driver set to scripting 2 + // Return nil + return 0; + } + new_ScriptingCANBuffer(L); *((ScriptingCANBuffer**)luaL_checkudata(L, -1, "ScriptingCANBuffer")) = scripting->_CAN_dev2->add_buffer(buffer_len); diff --git a/libraries/AP_Scripting/tests/docs_check.py b/libraries/AP_Scripting/tests/docs_check.py index a8bc1320dda21..f2c6b120b3da4 100644 --- a/libraries/AP_Scripting/tests/docs_check.py +++ b/libraries/AP_Scripting/tests/docs_check.py @@ -6,14 +6,16 @@ AP_FLAKE8_CLEAN ''' -import optparse, sys +import optparse, sys, re class method(object): - def __init__(self, global_name, local_name, num_args, full_line): + def __init__(self, global_name, local_name, num_args, full_line, returns, params): self.global_name = global_name self.local_name = local_name self.num_args = num_args self.full_line = full_line + self.returns = returns + self.params = params def __str__(self): ret_str = "%s\n" % (self.full_line) @@ -22,20 +24,91 @@ def __str__(self): ret_str += "\tFunction: %s\n" % (self.local_name) else: ret_str += "\tGlobal: %s\n" % (self.global_name) - ret_str += "\tNum Args: %s\n\n" % (self.num_args) + ret_str += "\tNum Args: %s\n" % (self.num_args) + + ret_str += "\tParams:\n" + for param_type in self.params: + ret_str += "\t\t%s\n" % param_type + + ret_str += "\tReturns:\n" + for return_type in self.returns: + ret_str += "\t\t%s\n" % return_type + + ret_str +="\n" return ret_str + def type_compare(self, A, B): + if (((len(A) == 1) and (A[0] == 'UNKNOWN')) or + ((len(B) == 1) and (B[0] == 'UNKNOWN'))): + # UNKNOWN is a special case used for manual bindings + return True + + if len(A) != len(B): + return False + + for i in range(len(A)): + if A[i] != B[i]: + return False + + return True + + def types_compare(self, A, B): + if len(A) != len(B): + return False + + for i in range(len(A)): + if not self.type_compare(A[i], B[i]): + return False + + return True + + def check_types(self, other): + if not self.types_compare(self.returns, other.returns): + return False + + if not self.types_compare(self.params, other.params): + return False + + return True + def __eq__(self, other): return (self.global_name == other.global_name) and (self.local_name == other.local_name) and (self.num_args == other.num_args) +def get_return_type(line): + try: + match = re.findall("^---@return (\w+(\|(\w+))*)", line) + all_types = match[0][0] + return all_types.split("|") + + except: + raise Exception("Could not get return type in: %s" % line) + +def get_param_type(line): + try: + match = re.findall("^---@param \w+\?? (\w+(\|(\w+))*)", line) + all_types = match[0][0] + return all_types.split("|") + + except: + raise Exception("Could not get param type in: %s" % line) + def parse_file(file_name): methods = [] + returns = [] + params = [] with open(file_name) as fp: while True: line = fp.readline() if not line: break + # Acuminate return and params to associate with next function + if line.startswith("---@return"): + returns.append(get_return_type(line)) + + if line.startswith("---@param"): + params.append(get_param_type(line)) + # only consider functions if not line.startswith("function"): continue @@ -57,12 +130,18 @@ def parse_file(file_name): # get arguments function_name, args = function_line.split("(",1) - args = args[0:args.find(")")-1] + args = args[0:args.find(")")] if len(args) == 0: num_args = 0 else: num_args = args.count(",") + 1 + # ... shows up in arg list but not @param, add a unknown param + if args.endswith("..."): + params.append(["UNKNOWN"]) + + if num_args != len(params): + raise Exception("Missing \"---@param\" for function: %s", line) # get global/class name and function name local_name = "" @@ -71,7 +150,9 @@ def parse_file(file_name): else: global_name = function_name - methods.append(method(global_name, local_name, num_args, line)) + methods.append(method(global_name, local_name, num_args, line, returns, params)) + returns = [] + params = [] return methods @@ -92,6 +173,15 @@ def compare(expected_file_name, got_file_name): print("Multiple definitions of:") print(meth) pass_check = False + + elif not meth.check_types(got): + print("Type error:") + print("Want:") + print(meth) + print("Got:") + print(got) + pass_check = False + found = True if not found: diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index d2aab8bf1d8ab..48966bfbe161c 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -77,7 +77,14 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @Range: 0 50 // @User: Advanced AP_GROUPINFO("OFS_MAX", 4, AP_Terrain, offset_max, 30), - + + // @Param: CACHE_SZ + // @DisplayName: Terrain cache size + // @Description: The number of 32x28 cache blocks to keep in memory. Each block uses about 1800 bytes of memory + // @Range: 0 128 + // @User: Advanced + AP_GROUPINFO("CACHE_SZ", 5, AP_Terrain, config_cache_size, TERRAIN_GRID_BLOCK_CACHE_SIZE), + AP_GROUPEND }; @@ -488,13 +495,13 @@ bool AP_Terrain::allocate(void) if (cache != nullptr) { return true; } - cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0])); + cache = (struct grid_cache *)calloc(config_cache_size, sizeof(cache[0])); if (cache == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); memory_alloc_failed = true; return false; } - cache_size = TERRAIN_GRID_BLOCK_CACHE_SIZE; + cache_size = config_cache_size; return true; } diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 8a6be4579db06..7dfd2653d8475 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -51,7 +51,9 @@ #define TERRAIN_GRID_BLOCK_SIZE_Y (TERRAIN_GRID_MAVLINK_SIZE*TERRAIN_GRID_BLOCK_MUL_Y) // number of grid_blocks in the LRU memory cache +#ifndef TERRAIN_GRID_BLOCK_CACHE_SIZE #define TERRAIN_GRID_BLOCK_CACHE_SIZE 12 +#endif // format of grid on disk #define TERRAIN_GRID_FORMAT_VERSION 1 @@ -371,6 +373,7 @@ class AP_Terrain { AP_Int16 grid_spacing; // meters between grid points AP_Int16 options; // option bits AP_Float offset_max; + AP_Int16 config_cache_size; enum class Options { DisableDownload = (1U<<0), diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index 5ff6b672b9ee1..1aac8d689cee0 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -19,86 +19,25 @@ #include #include -#include -#include #include -#include - -#define TORQEEDO_SERIAL_BAUD 19200 // communication is always at 19200 -#define TORQEEDO_PACKET_HEADER 0xAC // communication packet header -#define TORQEEDO_PACKET_FOOTER 0xAD // communication packet footer -#define TORQEEDO_PACKET_ESCAPE 0xAE // escape character for handling occurrences of header, footer and this escape bytes in original message -#define TORQEEDO_PACKET_ESCAPE_MASK 0x80 // byte after ESCAPE character should be XOR'd with this value -#define TORQEEDO_LOG_TRQD_INTERVAL_MS 5000// log TRQD message at this interval in milliseconds -#define TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS 100 // motor speed sent at 10hz if connected to motor -#define TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS 400 // motor status requested every 0.4sec if connected to motor -#define TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS 400 // motor param requested every 0.4sec if connected to motor -#define TORQEEDO_BATT_TIMEOUT_MS 5000 // battery info timeouts after 5 seconds -#define TORQEEDO_REPLY_TIMEOUT_MS 25 // stop waiting for replies after 25ms -#define TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS 10000 // errors reported to user at no less than once every 10 seconds +#include "AP_Torqeedo_Backend.h" +#include "AP_Torqeedo_TQBus.h" extern const AP_HAL::HAL& hal; -// parameters const AP_Param::GroupInfo AP_Torqeedo::var_info[] = { - // @Param: TYPE - // @DisplayName: Torqeedo connection type - // @Description: Torqeedo connection type - // @Values: 0:Disabled, 1:Tiller, 2:Motor - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO_FLAGS("TYPE", 1, AP_Torqeedo, _type, (int8_t)ConnectionType::TYPE_DISABLED, AP_PARAM_FLAG_ENABLE), - - // @Param: ONOFF_PIN - // @DisplayName: Torqeedo ON/Off pin - // @Description: Pin number connected to Torqeedo's on/off pin. -1 to use serial port's RTS pin if available - // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO("ONOFF_PIN", 2, AP_Torqeedo, _pin_onoff, -1), - - // @Param: DE_PIN - // @DisplayName: Torqeedo DE pin - // @Description: Pin number connected to RS485 to Serial converter's DE pin. -1 to use serial port's CTS pin if available - // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 - // @User: Standard - // @RebootRequired: True - AP_GROUPINFO("DE_PIN", 3, AP_Torqeedo, _pin_de, -1), - - // @Param: OPTIONS - // @DisplayName: Torqeedo Options - // @Description: Torqeedo Options Bitmask - // @Bitmask: 0:Log,1:Send debug to GCS - // @User: Advanced - AP_GROUPINFO("OPTIONS", 4, AP_Torqeedo, _options, (int8_t)options::LOG), + // 1 to 7 were used for parameters before frontend/backend split - // @Param: POWER - // @DisplayName: Torqeedo Motor Power - // @Description: Torqeedo motor power. Only applied when using motor connection type (e.g. TRQD_TYPE=2) - // @Units: % - // @Range: 0 100 - // @Increment: 1 - // @User: Advanced - AP_GROUPINFO("POWER", 5, AP_Torqeedo, _motor_power, 100), + // @Group: 1_ + // @Path: AP_Torqeedo_Params.cpp + AP_SUBGROUPINFO(_params[0], "1_", 8, AP_Torqeedo, AP_Torqeedo_Params), - // @Param: SLEW_TIME - // @DisplayName: Torqeedo Throttle Slew Time - // @Description: Torqeedo slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. Higher values cause a slower response, lower values cause a faster response. A value of zero disables the limit - // @Units: s - // @Range: 0 5 - // @Increment: 0.1 - // @User: Advanced - AP_GROUPINFO("SLEW_TIME", 6, AP_Torqeedo, _slew_time, 2.0), - - // @Param: DIR_DELAY - // @DisplayName: Torqeedo Direction Change Delay - // @Description: Torqeedo direction change delay. Output will remain at zero for this many seconds when transitioning between forward and backwards rotation - // @Units: s - // @Range: 0 5 - // @Increment: 0.1 - // @User: Advanced - AP_GROUPINFO("DIR_DELAY", 7, AP_Torqeedo, _dir_delay, 1.0), +#if AP_TORQEEDO_MAX_INSTANCES > 1 + // @Group: 2_ + // @Path: AP_Torqeedo_Params.cpp + AP_SUBGROUPINFO(_params[1], "2_", 9, AP_Torqeedo, AP_Torqeedo_Params), +#endif AP_GROUPEND }; @@ -112,156 +51,87 @@ AP_Torqeedo::AP_Torqeedo() // initialise driver void AP_Torqeedo::init() { - // exit immediately if not enabled - if (!enabled()) { - return; + // check init has not been called before + for (uint8_t i = 1; i < AP_TORQEEDO_MAX_INSTANCES; i++) { + if (get_instance(i) != nullptr) { + return; + } } - // only init once - // Note: a race condition exists here if init is called multiple times quickly before thread_main has a chance to set _initialise - if (_initialised) { - return; + // create each instance + uint8_t instance; + for (instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + switch ((ConnectionType)_params[instance].type.get()) { + case ConnectionType::TYPE_DISABLED: + // do nothing + break; + case ConnectionType::TYPE_TILLER: + case ConnectionType::TYPE_MOTOR: + _backends[instance] = new AP_Torqeedo_TQBus(_params[instance], instance); + break; + } } - // create background thread to process serial input and output - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Torqeedo::thread_main, void), "torqeedo", 2048, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) { - return; + // init each instance, do it after all instances were created, so that they all know things + for (instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->init(); + } } } -// initialise serial port and gpio pins (run from background thread) -bool AP_Torqeedo::init_internals() +// returns true if at least one backend has been configured (e.g. TYPE param has been set) +bool AP_Torqeedo::enabled() const { - // find serial driver and initialise - const AP_SerialManager &serial_manager = AP::serialmanager(); - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Torqeedo, 0); - if (_uart == nullptr) { - return false; - } - _uart->begin(TORQEEDO_SERIAL_BAUD); - _uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); - _uart->set_unbuffered_writes(true); - - // if using tiller connection set on/off pin for 0.5 sec to turn on battery - if (_type == ConnectionType::TYPE_TILLER) { - if (_pin_onoff > -1) { - hal.gpio->pinMode(_pin_onoff, HAL_GPIO_OUTPUT); - hal.gpio->write(_pin_onoff, 1); - hal.scheduler->delay(500); - hal.gpio->write(_pin_onoff, 0); - } else { - // use serial port's RTS pin to turn on battery - _uart->set_RTS_pin(true); - hal.scheduler->delay(500); - _uart->set_RTS_pin(false); + for (uint8_t instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + if (enabled(instance)) { + return true; } } - - // initialise RS485 DE pin (when high, allows send to motor) - if (_pin_de > -1) { - hal.gpio->pinMode(_pin_de, HAL_GPIO_OUTPUT); - hal.gpio->write(_pin_de, 0); - } else { - _uart->set_CTS_pin(false); - } - - return true; + return false; } -// returns true if the driver is enabled -bool AP_Torqeedo::enabled() const +// returns true if the instance has been configured (e.g. TYPE param has been set) +bool AP_Torqeedo::enabled(uint8_t instance) const { - switch ((ConnectionType)_type) { - case ConnectionType::TYPE_DISABLED: - return false; - case ConnectionType::TYPE_TILLER: - case ConnectionType::TYPE_MOTOR: - return true; + if (instance < AP_TORQEEDO_MAX_INSTANCES) { + switch ((ConnectionType)_params[instance].type.get()) { + case ConnectionType::TYPE_DISABLED: + return false; + case ConnectionType::TYPE_TILLER: + case ConnectionType::TYPE_MOTOR: + return true; + } } - return false; } -// consume incoming messages from motor, reply with latest motor speed -// runs in background thread -void AP_Torqeedo::thread_main() +// returns true if all backends are communicating with the motor +bool AP_Torqeedo::healthy() { - // initialisation - if (!init_internals()) { - return; - } - _initialised = true; - - while (true) { - // 1ms loop delay - hal.scheduler->delay_microseconds(1000); - - // check if transmit pin should be unset - check_for_send_end(); - - // check for timeout waiting for reply - check_for_reply_timeout(); - - // parse incoming characters - uint32_t nbytes = MIN(_uart->available(), 1024U); - while (nbytes-- > 0) { - int16_t b = _uart->read(); - if (b >= 0 ) { - if (parse_byte((uint8_t)b)) { - // complete message received, parse it! - parse_message(); - // clear wait-for-reply because if we are waiting for a reply, this message must be it - set_reply_received(); - } - } - } - - // send motor speed - bool log_update = false; - if (safe_to_send()) { - uint32_t now_ms = AP_HAL::millis(); - - // if connected to motor - if (_type == ConnectionType::TYPE_MOTOR) { - if (now_ms - _last_send_motor_ms > TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS) { - // send motor speed every 0.1sec - _send_motor_speed = true; - } else if (now_ms - _last_send_motor_status_request_ms > TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS) { - // send request for motor status - send_motor_msg_request(MotorMsgId::STATUS); - _last_send_motor_status_request_ms = now_ms; - } else if (now_ms - _last_send_motor_param_request_ms > TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS) { - // send request for motor params - send_motor_msg_request(MotorMsgId::PARAM); - _last_send_motor_param_request_ms = now_ms; - } - } - - // send motor speed - if (_send_motor_speed) { - send_motor_speed_cmd(); - _send_motor_speed = false; - log_update = true; + uint8_t num_backends = 0; + uint8_t num_healthy = 0; + for (uint8_t instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + auto *backend = get_instance(instance); + if (backend != nullptr) { + num_backends++; + if (backend->healthy()) { + num_healthy++; } } - - // log high level status and motor speed - log_TRQD(log_update); } + + return ((num_backends > 0) && (num_healthy == num_backends)); } -// returns true if communicating with the motor -bool AP_Torqeedo::healthy() +// returns true if instance is healthy +bool AP_Torqeedo::healthy(uint8_t instance) { - if (!_initialised) { + auto *backend = get_instance(instance); + if (backend == nullptr) { return false; } - { - // healthy if both receive and send have occurred in the last 3 seconds - WITH_SEMAPHORE(_last_healthy_sem); - const uint32_t now_ms = AP_HAL::millis(); - return ((now_ms - _last_received_ms < 3000) && (now_ms - _last_send_motor_ms < 3000)); - } + return backend->healthy(); } // run pre-arm check. returns false on failure and fills in failure_msg @@ -273,10 +143,6 @@ bool AP_Torqeedo::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } - if (!_initialised) { - strncpy(failure_msg, "not initialised", failure_msg_len); - return false; - } if (!healthy()) { strncpy(failure_msg, "not healthy", failure_msg_len); return false; @@ -284,870 +150,58 @@ bool AP_Torqeedo::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } -// returns a human-readable string corresponding the passed-in -// master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) -// If no conversion is available then nullptr is returned -const char * AP_Torqeedo::map_master_error_code_to_string(uint8_t code) const +// clear motor errors +void AP_Torqeedo::clear_motor_error() { - switch (code) { - case 2: - return "stator high temp"; - case 5: - return "propeller blocked"; - case 6: - return "motor low voltage"; - case 7: - return "motor high current"; - case 8: - return "pcb temp high"; - case 21: - return "tiller cal bad"; - case 22: - return "mag bad"; - case 23: - return "range incorrect"; - case 30: - return "motor comm error"; - case 32: - return "tiller comm error"; - case 33: - return "general comm error"; - case 41: - case 42: - return "charge voltage bad"; - case 43: - return "battery flat"; - case 45: - return "battery high current"; - case 46: - return "battery temp error"; - case 48: - return "charging temp error"; - } - - return nullptr; -} - -// report changes in error codes to user -void AP_Torqeedo::report_error_codes() -{ - // skip reporting if we have already reported status very recently - const uint32_t now_ms = AP_HAL::millis(); - - // skip reporting if no changes in flags and already reported within 10 seconds - const bool flags_changed = (_display_system_state_flags_prev.value != _display_system_state.flags.value) || - (_display_system_state_master_error_code_prev != _display_system_state.master_error_code) || - (_motor_status_prev.status_flags_value != _motor_status.status_flags_value) || - (_motor_status_prev.error_flags_value != _motor_status.error_flags_value); - if (!flags_changed && ((now_ms - _last_error_report_ms) < TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS)) { - return; - } - - // report display system errors - const char* msg_prefix = "Torqeedo:"; - (void)msg_prefix; // sometimes unused when HAL_GCS_ENABLED is false - if (_display_system_state.flags.set_throttle_stop) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix); - } - if (_display_system_state.flags.temp_warning) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); - } - if (_display_system_state.flags.batt_nearly_empty) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix); - } - if (_display_system_state.master_error_code > 0) { - const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code); - if (error_string != nullptr) { - GCS_SEND_TEXT( - MAV_SEVERITY_CRITICAL, "%s err:%u %s", - msg_prefix, - _display_system_state.master_error_code, - error_string); - } else { - GCS_SEND_TEXT( - MAV_SEVERITY_CRITICAL, "%s err:%u", - msg_prefix, - _display_system_state.master_error_code); + for (uint8_t instance = 0; instance < AP_TORQEEDO_MAX_INSTANCES; instance++) { + auto *backend = get_instance(instance); + if (backend != nullptr) { + backend->clear_motor_error(); } } - - // report motor status errors - if (_motor_status.error_flags.overcurrent) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix); - } - if (_motor_status.error_flags.blocked) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s prop blocked", msg_prefix); - } - if (_motor_status.error_flags.overvoltage_static || _motor_status.error_flags.overvoltage_current) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high voltage", msg_prefix); - } - if (_motor_status.error_flags.undervoltage_static || _motor_status.error_flags.undervoltage_current) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s low voltage", msg_prefix); - } - if (_motor_status.error_flags.overtemp_motor || _motor_status.error_flags.overtemp_pcb) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); - } - if (_motor_status.error_flags.timeout_rs485) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s comm timeout", msg_prefix); - } - if (_motor_status.error_flags.temp_sensor_error) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s temp sensor err", msg_prefix); - } - if (_motor_status.error_flags.tilt) { - GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix); - } - - // display OK if all errors cleared - const bool prev_errored = (_display_system_state_flags_prev.value != 0) || - (_display_system_state_master_error_code_prev != 0) || - (_motor_status_prev.error_flags_value != 0); - - const bool now_errored = (_display_system_state.flags.value != 0) || - (_display_system_state.master_error_code != 0) || - (_motor_status.error_flags_value != 0); - - if (!now_errored && prev_errored) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s OK", msg_prefix); - } - - // record change in state and reporting time - _display_system_state_flags_prev.value = _display_system_state.flags.value; - _display_system_state_master_error_code_prev = _display_system_state.master_error_code; - _motor_status_prev = _motor_status; - _last_error_report_ms = now_ms; } // get latest battery status info. returns true on success and populates arguments -bool AP_Torqeedo::get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const +// instance is normally 0 or 1, if invalid instances are provided the first instance is used +bool AP_Torqeedo::get_batt_info(uint8_t instance, float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const { - - // use battery info from display_system_state if available (tiller connection) - if ((AP_HAL::millis() - _display_system_state.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { - voltage = _display_system_state.batt_voltage; - current_amps = _display_system_state.batt_current; - temp_C = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); - pct_remaining = _display_system_state.batt_charge_pct; - return true; + // for invalid instances use the first instance + if (instance > AP_TORQEEDO_MAX_INSTANCES-1) { + instance = 0; } - // use battery info from motor_param if available (motor connection) - if ((AP_HAL::millis() - _motor_param.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { - voltage = _motor_param.voltage; - current_amps = _motor_param.current; - temp_C = MAX(_motor_param.pcb_temp, _motor_param.stator_temp); - pct_remaining = 0; // motor does not know percent remaining - return true; + // return battery info for specified instance + auto *backend = get_instance(instance); + if (backend != nullptr) { + return backend->get_batt_info(voltage, current_amps, temp_C, pct_remaining); } - return false; } // get battery capacity. returns true on success and populates argument -bool AP_Torqeedo::get_batt_capacity_Ah(uint16_t &_hours) const -{ - if (_display_system_setup.batt_capacity == 0) { - return false; - } - amp_hours = _display_system_setup.batt_capacity; - return true; -} - -// process a single byte received on serial port -// return true if a complete message has been received (the message will be held in _received_buff) -bool AP_Torqeedo::parse_byte(uint8_t b) -{ - bool complete_msg_received = false; - - switch (_parse_state) { - case ParseState::WAITING_FOR_HEADER: - if (b == TORQEEDO_PACKET_HEADER) { - _parse_state = ParseState::WAITING_FOR_FOOTER; - } - _received_buff_len = 0; - _parse_escape_received = false; - break; - case ParseState::WAITING_FOR_FOOTER: - if (b == TORQEEDO_PACKET_FOOTER) { - _parse_state = ParseState::WAITING_FOR_HEADER; - - // check message length - if (_received_buff_len == 0) { - _parse_error_count++; - break; - } - - // check crc - const uint8_t crc_expected = crc8_maxim(_received_buff, _received_buff_len-1); - if (_received_buff[_received_buff_len-1] != crc_expected) { - _parse_error_count++; - break; - } - _parse_success_count++; - { - // record time of successful receive for health reporting - WITH_SEMAPHORE(_last_healthy_sem); - _last_received_ms = AP_HAL::millis(); - } - complete_msg_received = true; - } else { - // escape character handling - if (_parse_escape_received) { - b ^= TORQEEDO_PACKET_ESCAPE_MASK; - _parse_escape_received = false; - } else if (b == TORQEEDO_PACKET_ESCAPE) { - // escape character received, record this and ignore this byte - _parse_escape_received = true; - break; - } - // add to buffer - _received_buff[_received_buff_len] = b; - _received_buff_len++; - if (_received_buff_len > TORQEEDO_MESSAGE_LEN_MAX) { - // message too long - _parse_state = ParseState::WAITING_FOR_HEADER; - _parse_error_count++; - } - } - break; - } - - return complete_msg_received; -} - -// process message held in _received_buff -void AP_Torqeedo::parse_message() -{ - // message address (i.e. target of message) - const MsgAddress msg_addr = (MsgAddress)_received_buff[0]; - - // handle messages sent to "remote" (aka tiller) - if ((_type == ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::REMOTE1)) { - RemoteMsgId msg_id = (RemoteMsgId)_received_buff[1]; - if (msg_id == RemoteMsgId::REMOTE) { - // request received to send updated motor speed - _send_motor_speed = true; - } - return; - } - - // handle messages sent to Display - if ((_type == ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::DISPLAY)) { - DisplayMsgId msg_id = (DisplayMsgId)_received_buff[1]; - switch (msg_id) { - case DisplayMsgId::SYSTEM_STATE : - if (_received_buff_len == 30) { - // fill in _display_system_state - _display_system_state.flags.value = UINT16_VALUE(_received_buff[2], _received_buff[3]); - _display_system_state.master_state = _received_buff[4]; // deprecated - _display_system_state.master_error_code = _received_buff[5]; - _display_system_state.motor_voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; - _display_system_state.motor_current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; - _display_system_state.motor_power = UINT16_VALUE(_received_buff[10], _received_buff[11]); - _display_system_state.motor_rpm = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]); - _display_system_state.motor_pcb_temp = _received_buff[14]; - _display_system_state.motor_stator_temp = _received_buff[15]; - _display_system_state.batt_charge_pct = _received_buff[16]; - _display_system_state.batt_voltage = UINT16_VALUE(_received_buff[17], _received_buff[18]) * 0.01; - _display_system_state.batt_current = UINT16_VALUE(_received_buff[19], _received_buff[20]) * 0.1; - _display_system_state.gps_speed = UINT16_VALUE(_received_buff[21], _received_buff[22]); - _display_system_state.range_miles = UINT16_VALUE(_received_buff[23], _received_buff[24]); - _display_system_state.range_minutes = UINT16_VALUE(_received_buff[25], _received_buff[26]); - _display_system_state.temp_sw = _received_buff[27]; - _display_system_state.temp_rp = _received_buff[28]; - _display_system_state.last_update_ms = AP_HAL::millis(); - - // update esc telem sent to ground station - const uint8_t esc_temp = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); - const uint8_t motor_temp = MAX(_display_system_state.motor_pcb_temp, _display_system_state.motor_stator_temp); - update_esc_telem(_display_system_state.motor_rpm, - _display_system_state.motor_voltage, - _display_system_state.motor_current, - esc_temp, - motor_temp); - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRST - // @Description: Torqeedo System State - // @Field: TimeUS: Time since system startup - // @Field: F: Flags bitmask - // @Field: Err: Master error code - // @Field: MVolt: Motor voltage - // @Field: MCur: Motor current - // @Field: Pow: Motor power - // @Field: RPM: Motor RPM - // @Field: MTemp: Motor Temp (higher of pcb or stator) - // @Field: BPct: Battery charge percentage - // @Field: BVolt: Battery voltage - // @Field: BCur: Battery current - AP::logger().Write("TRST", "TimeUS,F,Err,MVolt,MCur,Pow,RPM,MTemp,BPct,BVolt,BCur", "QHBffHhBBff", - AP_HAL::micros64(), - _display_system_state.flags.value, - _display_system_state.master_error_code, - _display_system_state.motor_voltage, - _display_system_state.motor_current, - _display_system_state.motor_power, - _display_system_state.motor_rpm, - motor_temp, - _display_system_state.batt_charge_pct, - _display_system_state.batt_voltage, - _display_system_state.batt_current); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRST F:%u Err:%u MV:%4.1f MC:%4.1f P:%u MT:%d B%%:%d BV:%4.1f BC:%4.1f", - (unsigned)_display_system_state.flags.value, - (unsigned)_display_system_state.master_error_code, - (double)_display_system_state.motor_voltage, - (double)_display_system_state.motor_current, - (unsigned)_display_system_state.motor_power, - (int)motor_temp, - (unsigned)_display_system_state.batt_charge_pct, - (double)_display_system_state.batt_voltage, - (double)_display_system_state.batt_current); - } - - // report any errors - report_error_codes(); - } else { - // unexpected length - _parse_error_count++; - } - break; - case DisplayMsgId::SYSTEM_SETUP: - if (_received_buff_len == 13) { - // fill in display system setup - _display_system_setup.flags = _received_buff[2]; - _display_system_setup.motor_type = _received_buff[3]; - _display_system_setup.motor_sw_version = UINT16_VALUE(_received_buff[4], _received_buff[5]); - _display_system_setup.batt_capacity = UINT16_VALUE(_received_buff[6], _received_buff[7]); - _display_system_setup.batt_charge_pct = _received_buff[8]; - _display_system_setup.batt_type = _received_buff[9]; - _display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]); - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRSE - // @Description: Torqeedo System Setup - // @Field: TimeUS: Time since system startup - // @Field: Flag: Flags - // @Field: MotType: Motor type - // @Field: MotVer: Motor software version - // @Field: BattCap: Battery capacity - // @Field: BattPct: Battery charge percentage - // @Field: BattType: Battery type - // @Field: SwVer: Master software version - AP::logger().Write("TRSE", "TimeUS,Flag,MotType,MotVer,BattCap,BattPct,BattType,SwVer", "QBBHHBBH", - AP_HAL::micros64(), - _display_system_setup.flags, - _display_system_setup.motor_type, - _display_system_setup.motor_sw_version, - _display_system_setup.batt_capacity, - _display_system_setup.batt_charge_pct, - _display_system_setup.batt_type, - _display_system_setup.master_sw_version); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRSE:%u F:%u Mot:%u/%u Bat:%u/%u/%u%%", - (unsigned)_display_system_setup.master_sw_version, - (unsigned)_display_system_setup.flags, - (unsigned)_display_system_setup.motor_type, - (unsigned)_display_system_setup.motor_sw_version, - (unsigned)_display_system_setup.batt_type, - (unsigned)_display_system_setup.batt_capacity, - (unsigned)_display_system_setup.batt_charge_pct); - } - } else { - // unexpected length - _parse_error_count++; - } - break; - default: - // ignore message - break; - } - return; - } - - // handle reply from motor - if ((_type == ConnectionType::TYPE_MOTOR) && (msg_addr == MsgAddress::BUS_MASTER)) { - // replies strangely do not return the msgid so we must have stored it - MotorMsgId msg_id = (MotorMsgId)_reply_msgid; - switch (msg_id) { - - case MotorMsgId::PARAM: - if (_received_buff_len == 15) { - _motor_param.rpm = (int16_t)UINT16_VALUE(_received_buff[2], _received_buff[3]); - _motor_param.power = UINT16_VALUE(_received_buff[4], _received_buff[5]); - _motor_param.voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; - _motor_param.current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; - _motor_param.pcb_temp = (int16_t)UINT16_VALUE(_received_buff[10], _received_buff[11]) * 0.1; - _motor_param.stator_temp = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]) * 0.1; - _motor_param.last_update_ms = AP_HAL::millis(); - - // update esc telem sent to ground station - update_esc_telem(_motor_param.rpm, - _motor_param.voltage, - _motor_param.current, - _motor_param.pcb_temp, // esc temp - _motor_param.stator_temp); // motor temp - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRMP - // @Description: Torqeedo Motor Param - // @Field: TimeUS: Time since system startup - // @Field: RPM: Motor RPM - // @Field: Pow: Motor power - // @Field: Volt: Motor voltage - // @Field: Cur: Motor current - // @Field: ETemp: ESC Temp - // @Field: MTemp: Motor Temp - AP::logger().Write("TRMP", "TimeUS,RPM,Pow,Volt,Cur,ETemp,MTemp", "QhHffff", - AP_HAL::micros64(), - _motor_param.rpm, - _motor_param.power, - _motor_param.voltage, - _motor_param.current, - _motor_param.pcb_temp, - _motor_param.stator_temp); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRMP: rpm:%d p:%u V:%4.1f C:%4.1f PT:%4.1f MT:%4.1f", - (int)_motor_param.rpm, - (unsigned)_motor_param.power, - (double)_motor_param.voltage, - (double)_motor_param.current, - (double)_motor_param.pcb_temp, - (double)_motor_param.stator_temp); - } - } else { - // unexpected length - _parse_error_count++; - } - break; - - case MotorMsgId::STATUS: - if (_received_buff_len == 6) { - _motor_status.status_flags_value = _received_buff[2]; - _motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]); - -#if HAL_LOGGING_ENABLED - // log data - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRMS - // @Description: Torqeedo Motor Status - // @Field: TimeUS: Time since system startup - // @Field: State: Motor status flags - // @Field: Err: Motor error flags - AP::logger().Write("TRMS", "TimeUS,State,Err", "QBH", - AP_HAL::micros64(), - _motor_status.status_flags_value, - _motor_status.error_flags_value); - } -#endif - - // send to GCS - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRMS S:%d Err:%d", - _motor_status.status_flags_value, - _motor_status.error_flags_value); - } - - // report any errors - report_error_codes(); - } else { - // unexpected length - _parse_error_count++; - } - break; - - case MotorMsgId::INFO: - case MotorMsgId::DRIVE: - case MotorMsgId::CONFIG: - // we do not process these replies - break; - - default: - // ignore unknown messages - break; - } - } -} - -// set DE Serial CTS pin to enable sending commands to motor -void AP_Torqeedo::send_start() -{ - // set gpio pin or serial port's CTS pin - if (_pin_de > -1) { - hal.gpio->write(_pin_de, 1); - } else { - _uart->set_CTS_pin(true); - } -} - -// check for timeout after sending and unset pin if required -void AP_Torqeedo::check_for_send_end() -{ - if (_send_delay_us == 0) { - // not sending - return; - } - - if (AP_HAL::micros() - _send_start_us < _send_delay_us) { - // return if delay has not yet elapsed - return; - } - _send_delay_us = 0; - - // unset gpio or serial port's CTS pin - if (_pin_de > -1) { - hal.gpio->write(_pin_de, 0); - } else { - _uart->set_CTS_pin(false); - } -} - -// calculate delay require to allow bytes to be sent -uint32_t AP_Torqeedo::calc_send_delay_us(uint8_t num_bytes) -{ - // baud rate of 19200 bits/sec - // total number of bits = 10 x num_bytes - // convert from seconds to micros by multiplying by 1,000,000 - // plus additional 300us safety margin - const uint32_t delay_us = 1e6 * num_bytes * 10 / TORQEEDO_SERIAL_BAUD + 300; - return delay_us; -} - -// record msgid of message to wait for and set timer for timeout handling -void AP_Torqeedo::set_expected_reply_msgid(uint8_t msg_id) -{ - _reply_msgid = msg_id; - _reply_wait_start_ms = AP_HAL::millis(); -} - -// check for timeout waiting for reply message -void AP_Torqeedo::check_for_reply_timeout() +// instance is normally 0 or 1, if invalid instances are provided the first instance is used +bool AP_Torqeedo::get_batt_capacity_Ah(uint8_t instance, uint16_t &_hours) const { - // return immediately if not waiting for reply - if (_reply_wait_start_ms == 0) { - return; + // for invalid instances use the first instance + if (instance > AP_TORQEEDO_MAX_INSTANCES-1) { + instance = 0; } - if (AP_HAL::millis() - _reply_wait_start_ms > TORQEEDO_REPLY_TIMEOUT_MS) { - _reply_wait_start_ms = 0; - _parse_error_count++; - } -} - -// mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply -void AP_Torqeedo::set_reply_received() -{ - _reply_wait_start_ms = 0; -} - -// send a message to the motor with the specified message contents -// msg_contents should not include the header, footer or CRC -// returns true on success -bool AP_Torqeedo::send_message(const uint8_t msg_contents[], uint8_t num_bytes) -{ - // buffer for outgoing message - uint8_t send_buff[TORQEEDO_MESSAGE_LEN_MAX]; - uint8_t send_buff_num_bytes = 0; - - // calculate crc - const uint8_t crc = crc8_maxim(msg_contents, num_bytes); - // add header - send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_HEADER; - - // add contents - for (uint8_t i=0; iget_batt_capacity_Ah(amp_hours); } - - // add crc - if (!add_byte_to_message(crc, send_buff, ARRAY_SIZE(send_buff), send_buff_num_bytes)) { - _parse_error_count++; - return false; - } - - // add footer - if (send_buff_num_bytes >= ARRAY_SIZE(send_buff)) { - _parse_error_count++; - return false; - } - send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_FOOTER; - - // set send pin - send_start(); - - // write message - _uart->write(send_buff, send_buff_num_bytes); - - // record start and expected delay to send message - _send_start_us = AP_HAL::micros(); - _send_delay_us = calc_send_delay_us(send_buff_num_bytes); - - return true; -} - -// add a byte to a message buffer including adding the escape character (0xAE) if necessary -// this should only be used when adding the contents to the buffer, not the header and footer -// num_bytes is updated to the next free byte -bool AP_Torqeedo::add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const -{ - bool escape_required = (byte_to_add == TORQEEDO_PACKET_HEADER || - byte_to_add == TORQEEDO_PACKET_FOOTER || - byte_to_add == TORQEEDO_PACKET_ESCAPE); - - // check if we have enough space - if (num_bytes + (escape_required ? 2 : 1) >= msg_buff_size) { - return false; - } - - // add byte - if (escape_required) { - msg_buff[num_bytes++] = TORQEEDO_PACKET_ESCAPE; - msg_buff[num_bytes++] = byte_to_add ^ TORQEEDO_PACKET_ESCAPE_MASK; - } else { - msg_buff[num_bytes++] = byte_to_add; - } - return true; -} - -// Example "Remote (0x01)" reply message to allow tiller to control motor speed -// Byte Field Definition Example Value Comments -// --------------------------------------------------------------------------------- -// byte 0 Header 0xAC -// byte 1 TargetAddress 0x00 see MsgAddress enum -// byte 2 Message ID 0x00 only master populates this. replies have this set to zero -// byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid -// byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 -// byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) -// byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) -// byte 7 CRC-Maxim ---- CRC-Maxim value -// byte 8 Footer 0xAD -// -// example message when rotating tiller handle forwards: "AC 00 00 05 00 00 ED 95 AD" (+237) -// example message when rotating tiller handle backwards: "AC 00 00 05 00 FF AE 2C 0C AD" (-82) - -// send a motor speed command as a value from -1000 to +1000 -// value is taken directly from SRV_Channel -// for tiller connection this sends the "Remote (0x01)" message -// for motor connection this sends the "Motor Drive (0x82)" message -void AP_Torqeedo::send_motor_speed_cmd() -{ - // calculate desired motor speed - if (!hal.util->get_soft_armed()) { - _motor_speed_desired = 0; - } else { - // convert throttle output to motor output in range -1000 to +1000 - // ToDo: convert PWM output to motor output so that SERVOx_MIN, MAX and TRIM take effect - _motor_speed_desired = constrain_int16(SRV_Channels::get_output_norm(SRV_Channel::Aux_servo_function_t::k_throttle) * 1000.0, -1000, 1000); - } - - // updated limited motor speed - int16_t mot_speed_limited = calc_motor_speed_limited(_motor_speed_desired); - - // by default use tiller connection command - uint8_t mot_speed_cmd_buff[] = {(uint8_t)MsgAddress::BUS_MASTER, 0x0, 0x5, 0x0, HIGHBYTE(mot_speed_limited), LOWBYTE(mot_speed_limited)}; - - // update message if using motor connection - if (_type == ConnectionType::TYPE_MOTOR) { - const uint8_t motor_power = (uint8_t)constrain_int16(_motor_power, 0, 100); - mot_speed_cmd_buff[0] = (uint8_t)MsgAddress::MOTOR; - mot_speed_cmd_buff[1] = (uint8_t)MotorMsgId::DRIVE; - mot_speed_cmd_buff[2] = (mot_speed_limited == 0 ? 0 : 0x01) | (_motor_clear_error ? 0x04 : 0); // 1:enable motor, 2:fast off, 4:clear error - mot_speed_cmd_buff[3] = mot_speed_limited == 0 ? 0 : motor_power; // motor power from 0 to 100 - - // set expected reply message id - set_expected_reply_msgid((uint8_t)MotorMsgId::DRIVE); - - // reset motor clear error request - _motor_clear_error = false; - } - - // send a message - if (send_message(mot_speed_cmd_buff, ARRAY_SIZE(mot_speed_cmd_buff))) { - // record time of send for health reporting - WITH_SEMAPHORE(_last_healthy_sem); - _last_send_motor_ms = AP_HAL::millis(); - } -} - -// send request to motor to reply with a particular message -// msg_id can be INFO, STATUS or PARAM -void AP_Torqeedo::send_motor_msg_request(MotorMsgId msg_id) -{ - // prepare message - uint8_t mot_status_request_buff[] = {(uint8_t)MsgAddress::MOTOR, (uint8_t)msg_id}; - - // send a message - if (send_message(mot_status_request_buff, ARRAY_SIZE(mot_status_request_buff))) { - // record waiting for reply - set_expected_reply_msgid((uint8_t)msg_id); - } -} - -// calculate the limited motor speed that is sent to the motors -// desired_motor_speed argument and returned value are in the range -1000 to 1000 -int16_t AP_Torqeedo::calc_motor_speed_limited(int16_t desired_motor_speed) -{ - const uint32_t now_ms = AP_HAL::millis(); - - // update dir_limit flag for forward-reverse transition delay - const bool dir_delay_active = is_positive(_dir_delay); - if (!dir_delay_active) { - // allow movement in either direction - _dir_limit = 0; - } else { - // by default limit motor direction to previous iteration's direction - if (is_positive(_motor_speed_limited)) { - _dir_limit = 1; - } else if (is_negative(_motor_speed_limited)) { - _dir_limit = -1; - } else { - // motor speed is zero - if ((_motor_speed_zero_ms != 0) && ((now_ms - _motor_speed_zero_ms) > (_dir_delay * 1000))) { - // delay has passed so allow movement in either direction - _dir_limit = 0; - _motor_speed_zero_ms = 0; - } - } - } - - // calculate upper and lower limits for forward-reverse transition delay - int16_t lower_limit = -1000; - int16_t upper_limit = 1000; - if (_dir_limit < 0) { - upper_limit = 0; - } - if (_dir_limit > 0) { - lower_limit = 0; - } - - // calculate dt since last update - float dt = (now_ms - _motor_speed_limited_ms) * 0.001f; - if (dt > 1.0) { - // after a long delay limit motor output to zero to avoid sudden starts - lower_limit = 0; - upper_limit = 0; - } - _motor_speed_limited_ms = now_ms; - - // apply slew limit - if (_slew_time > 0) { - const float chg_max = 1000.0 * dt / _slew_time; - _motor_speed_limited = constrain_float(desired_motor_speed, _motor_speed_limited - chg_max, _motor_speed_limited + chg_max); - } else { - // no slew limit - _motor_speed_limited = desired_motor_speed; - } - - // apply upper and lower limits - _motor_speed_limited = constrain_float(_motor_speed_limited, lower_limit, upper_limit); - - // record time motor speed becomes zero - if (is_zero(_motor_speed_limited)) { - if (_motor_speed_zero_ms == 0) { - _motor_speed_zero_ms = now_ms; - } - } else { - // clear timer - _motor_speed_zero_ms = 0; - } - - return (int16_t)_motor_speed_limited; + return false; } -// output logging and debug messages (if required) -// force_logging should be true if caller wants to ensure the latest status is logged -void AP_Torqeedo::log_TRQD(bool force_logging) +// return pointer to backend given an instance number +AP_Torqeedo_Backend *AP_Torqeedo::get_instance(uint8_t instance) const { - // exit immediately if options are all unset - if (_options == 0) { - return; - } - - // return if not enough time has passed since last output - const uint32_t now_ms = AP_HAL::millis(); - if (!force_logging && (now_ms - _last_log_TRQD_ms < TORQEEDO_LOG_TRQD_INTERVAL_MS)) { - return; - } - _last_log_TRQD_ms = now_ms; - -#if HAL_LOGGING_ENABLED || HAL_GCS_ENABLED - const bool health = healthy(); - int16_t actual_motor_speed = get_motor_speed_limited(); - -#if HAL_LOGGING_ENABLED - if ((_options & options::LOG) != 0) { - // @LoggerMessage: TRQD - // @Description: Torqeedo Status - // @Field: TimeUS: Time since system startup - // @Field: Health: Health - // @Field: DesMotSpeed: Desired Motor Speed (-1000 to 1000) - // @Field: MotSpeed: Motor Speed (-1000 to 1000) - // @Field: SuccCnt: Success Count - // @Field: ErrCnt: Error Count - AP::logger().Write("TRQD", "TimeUS,Health,DesMotSpeed,MotSpeed,SuccCnt,ErrCnt", "QBhhII", - AP_HAL::micros64(), - health, - _motor_speed_desired, - actual_motor_speed, - _parse_success_count, - _parse_error_count); - } -#endif - - if ((_options & options::DEBUG_TO_GCS) != 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD h:%u dspd:%d spd:%d succ:%ld err:%ld", - (unsigned)health, - (int)_motor_speed_desired, - (int)actual_motor_speed, - (unsigned long)_parse_success_count, - (unsigned long)_parse_error_count); + if (instance < AP_TORQEEDO_MAX_INSTANCES) { + return _backends[instance]; } -#endif // HAL_LOGGING_ENABLED || HAL_GCS_ENABLED -} - -// send ESC telemetry -void AP_Torqeedo::update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC) -{ -#if HAL_WITH_ESC_TELEM - // find servo output channel - uint8_t telem_esc_index = 0; - IGNORE_RETURN(SRV_Channels::find_channel(SRV_Channel::Aux_servo_function_t::k_throttle, telem_esc_index)); - - // fill in telemetry data structure - AP_ESC_Telem_Backend::TelemetryData telem_dat {}; - telem_dat.temperature_cdeg = esc_tempC * 100; // temperature in centi-degrees - telem_dat.voltage = voltage; // voltage in volts - telem_dat.current = current_amps; // current in amps - telem_dat.motor_temp_cdeg = motor_tempC * 100; // motor temperature in centi-degrees - - // send telem and rpm data - update_telem_data(telem_esc_index, telem_dat, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | - AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | - AP_ESC_Telem_Backend::TelemetryType::CURRENT | - AP_ESC_Telem_Backend::TelemetryType::VOLTAGE); - - update_rpm(telem_esc_index, rpm); -#endif + return nullptr; } // get the AP_Torqeedo singleton @@ -1159,10 +213,11 @@ AP_Torqeedo *AP_Torqeedo::get_singleton() AP_Torqeedo *AP_Torqeedo::_singleton = nullptr; namespace AP { + AP_Torqeedo *torqeedo() { return AP_Torqeedo::get_singleton(); } -}; +} #endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.h b/libraries/AP_Torqeedo/AP_Torqeedo.h index 32d2a002c2892..f5c4eb1cb871f 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.h +++ b/libraries/AP_Torqeedo/AP_Torqeedo.h @@ -15,32 +15,7 @@ /* This driver supports communicating with Torqeedo motors that implement the "TQ Bus" protocol - which includes the Ultralight, Cruise 2.0 R, Cruise 4.0 R, Travel 503, Travel 1003 and Cruise 10kW - - The autopilot should be connected either to the battery's tiller connector or directly to the motor - as described on the ArduPilot wiki. https://ardupilot.org/rover/docs/common-torqeedo.html - TQ Bus is a serial protocol over RS-485 meaning that a serial to RS-485 converter is required. - - Tiller connection: Autopilot <-> Battery (master) <-> Motor - Motor connection: Autopilot (master) <-> Motor - - Communication between the components is always initiated by the master with replies sent within 25ms - - Example "Remote (0x01)" reply message to allow tiller to control motor speed - Byte Field Definition Example Value Comments - --------------------------------------------------------------------------------- - byte 0 Header 0xAC - byte 1 TargetAddress 0x00 see MsgAddress enum - byte 2 Message ID 0x00 only master populates this. replies have this set to zero - byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid - byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 - byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) - byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) - byte 7 CRC-Maxim ---- CRC-Maxim value - byte 8 Footer 0xAD - - More details of the TQ Bus protocol are available from Torqeedo after signing an NDA. - */ +*/ #pragma once @@ -48,84 +23,30 @@ #if HAL_TORQEEDO_ENABLED -#include #include +#include "AP_Torqeedo_Params.h" + +#define AP_TORQEEDO_MAX_INSTANCES 2 // maximum number of Torqeedo backends + +// declare backend classes +class AP_Torqeedo_Backend; +class AP_Torqeedo_TQBus; + +class AP_Torqeedo { -#define TORQEEDO_MESSAGE_LEN_MAX 35 // messages are no more than 35 bytes + // declare backends as friends + friend class AP_Torqeedo_Backend; + friend class AP_Torqeedo_TQBus; -class AP_Torqeedo : public AP_ESC_Telem_Backend { public: AP_Torqeedo(); + /* Do not allow copies */ CLASS_NO_COPY(AP_Torqeedo); + // get singleton instance static AP_Torqeedo* get_singleton(); - // initialise driver - void init(); - - // consume incoming messages from motor, reply with latest motor speed - // runs in background thread - void thread_main(); - - // returns true if communicating with the motor - bool healthy(); - - // run pre-arm check. returns false on failure and fills in failure_msg - // any failure_msg returned will not include a prefix - bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len); - - // report changes in error codes to user - void report_error_codes(); - - // clear motor errors - void clear_motor_error() { _motor_clear_error = true; } - - // get latest battery status info. returns true on success and populates arguments - bool get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const WARN_IF_UNUSED; - bool get_batt_capacity_Ah(uint16_t &_hours) const; - - static const struct AP_Param::GroupInfo var_info[]; - -private: - - // message addresses - enum class MsgAddress : uint8_t { - BUS_MASTER = 0x00, - REMOTE1 = 0x14, - DISPLAY = 0x20, - MOTOR = 0x30, - BATTERY = 0x80 - }; - - // Remote specific message ids - enum class RemoteMsgId : uint8_t { - INFO = 0x00, - REMOTE = 0x01, - SETUP = 0x02 - }; - - // Display specific message ids - enum class DisplayMsgId : uint8_t { - INFO = 0x00, - SYSTEM_STATE = 0x41, - SYSTEM_SETUP = 0x42 - }; - - // Motor specific message ids - enum class MotorMsgId : uint8_t { - INFO = 0x00, - STATUS = 0x01, - PARAM = 0x03, - CONFIG = 0x04, - DRIVE = 0x82 - }; - - enum class ParseState { - WAITING_FOR_HEADER = 0, - WAITING_FOR_FOOTER, - }; - // TYPE parameter values enum class ConnectionType : uint8_t { TYPE_DISABLED = 0, @@ -134,232 +55,47 @@ class AP_Torqeedo : public AP_ESC_Telem_Backend { }; // OPTIONS parameter values - enum options { + enum class options { LOG = 1<<0, DEBUG_TO_GCS = 1<<1, }; - // initialise serial port and gpio pins (run from background thread) - // returns true on success - bool init_internals(); + // initialise driver + void init(); - // returns true if the driver is enabled + // returns true if at least one backend has been configured (e.g. TYPE param has been set) bool enabled() const; + bool enabled(uint8_t instance) const; - // process a single byte received on serial port - // return true if a complete message has been received (the message will be held in _received_buff) - bool parse_byte(uint8_t b); - - // process message held in _received_buff - void parse_message(); - - // returns true if it is safe to send a message - bool safe_to_send() const { return ((_send_delay_us == 0) && (_reply_wait_start_ms == 0)); } - - // set pin to enable sending a message - void send_start(); - - // check for timeout after sending a message and unset pin if required - void check_for_send_end(); - - // calculate delay required to allow message to be completely sent - uint32_t calc_send_delay_us(uint8_t num_bytes); - - // record msgid of message to wait for and set timer for reply timeout handling - void set_expected_reply_msgid(uint8_t msg_id); - - // check for timeout waiting for reply - void check_for_reply_timeout(); - - // mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply - void set_reply_received(); - - // send a message to the motor with the specified message contents - // msg_contents should not include the header, footer or CRC - // returns true on success - bool send_message(const uint8_t msg_contents[], uint8_t num_bytes); - - // add a byte to a message buffer including adding the escape character (0xAE) if necessary - // this should only be used when adding the contents to the buffer, not the header and footer - // num_bytes is updated to the next free byte - bool add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const; - - // send a motor speed command as a value from -1000 to +1000 - // value is taken directly from SRV_Channel - void send_motor_speed_cmd(); - - // send request to motor to reply with a particular message - // msg_id can be INFO, STATUS or PARAM - void send_motor_msg_request(MotorMsgId msg_id); - - // calculate the limited motor speed that is sent to the motors - // desired_motor_speed argument and returned value are in the range -1000 to 1000 - int16_t calc_motor_speed_limited(int16_t desired_motor_speed); - int16_t get_motor_speed_limited() const { return (int16_t)_motor_speed_limited; } - - // log TRQD message which holds high level status and latest desired motors peed - // force_logging should be true to immediately write log bypassing timing check to avoid spamming - void log_TRQD(bool force_logging); - - // send ESC telemetry - void update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC); - - // parameters - AP_Enum _type; // connector type used (0:disabled, 1:tiller connector, 2: motor connector) - AP_Int8 _pin_onoff; // Pin number connected to Torqeedo's on/off pin. -1 to disable turning motor on/off from autopilot - AP_Int8 _pin_de; // Pin number connected to RS485 to Serial converter's DE pin. -1 to disable sending commands to motor - AP_Int16 _options; // options bitmask - AP_Int8 _motor_power; // motor power (0 ~ 100). only applied when using motor connection - AP_Float _slew_time; // slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. A value of zero disables the limit - AP_Float _dir_delay; // direction change delay. output will remain at zero for this many seconds when transitioning between forward and backwards rotation - - // members - AP_HAL::UARTDriver *_uart; // serial port to communicate with motor - bool _initialised; // true once driver has been initialised - bool _send_motor_speed; // true if motor speed should be sent at next opportunity - int16_t _motor_speed_desired; // desired motor speed (set from within update method) - uint32_t _last_send_motor_ms; // system time (in millis) last motor speed command was sent (used for health reporting) - bool _motor_clear_error; // true if the motor error should be cleared (sent in "Drive" message) - uint32_t _send_start_us; // system time (in micros) when last message started being sent (used for timing to unset DE pin) - uint32_t _send_delay_us; // delay (in micros) to allow bytes to be sent after which pin can be unset. 0 if not delaying - - // motor speed limit variables - float _motor_speed_limited; // limited desired motor speed. this value is actually sent to the motor - uint32_t _motor_speed_limited_ms; // system time that _motor_speed_limited was last updated - int8_t _dir_limit; // acceptable directions for output to motor (+1 = positive OK, -1 = negative OK, 0 = either positive or negative OK) - uint32_t _motor_speed_zero_ms; // system time that _motor_speed_limited reached zero. 0 if currently not zero - - // health reporting - HAL_Semaphore _last_healthy_sem;// semaphore protecting reading and updating of _last_send_motor_ms and _last_received_ms - uint32_t _last_log_TRQD_ms; // system time (in millis) that TRQD was last logged + // returns true if all backends are communicating with the motor + bool healthy(); + bool healthy(uint8_t instance); - // message parsing members - ParseState _parse_state; // current state of parsing - bool _parse_escape_received; // true if the escape character has been received so we must XOR the next byte - uint32_t _parse_error_count; // total number of parsing errors (for reporting) - uint32_t _parse_success_count; // number of messages successfully parsed (for reporting) - uint8_t _received_buff[TORQEEDO_MESSAGE_LEN_MAX]; // characters received - uint8_t _received_buff_len; // number of characters received - uint32_t _last_received_ms; // system time (in millis) that a message was successfully parsed (for health reporting) + // run pre-arm check. returns false on failure and fills in failure_msg + // any failure_msg returned will not include a prefix + bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len); - // reply message handling - uint8_t _reply_msgid; // replies expected msgid (reply often does not specify the msgid so we must record it) - uint32_t _reply_wait_start_ms; // system time that we started waiting for a reply message + // clear motor errors + void clear_motor_error(); - // Display system state flags - typedef union PACKED { - struct { - uint8_t set_throttle_stop : 1; // 0, warning that user must set throttle to stop before motor can run - uint8_t setup_allowed : 1; // 1, remote is allowed to enter setup mode - uint8_t in_charge : 1; // 2, master is in charging state - uint8_t in_setup : 1; // 3, master is in setup state - uint8_t bank_available : 1; // 4 - uint8_t no_menu : 1; // 5 - uint8_t menu_off : 1; // 6 - uint8_t reserved7 : 1; // 7, unused - uint8_t temp_warning : 1; // 8, motor or battery temp warning - uint8_t batt_charge_valid : 1; // 9, battery charge valid - uint8_t batt_nearly_empty : 1; // 10, battery nearly empty - uint8_t batt_charging : 1; // 11, battery charging - uint8_t gps_searching : 1; // 12, gps searching for satellites - uint8_t gps_speed_valid : 1; // 13, gps speed is valid - uint8_t range_miles_valid : 1; // 14, range (in miles) is valid - uint8_t range_minutes_valid : 1; // 15, range (in minutes) is valid - }; - uint16_t value; - } DisplaySystemStateFlags; + // get latest battery status info. returns true on success and populates arguments + // instance is normally 0 or 1, if invalid instances are provided the first instance is used + bool get_batt_info(uint8_t instance, float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const WARN_IF_UNUSED; + bool get_batt_capacity_Ah(uint8_t instance, uint16_t &_hours) const; - // Display system state - struct DisplaySystemState { - DisplaySystemStateFlags flags; // flags, see above for individual bit definitions - uint8_t master_state; // deprecated - uint8_t master_error_code; // error code (0=no error) - float motor_voltage; // motor voltage in volts - float motor_current; // motor current in amps - uint16_t motor_power; // motor power in watts - int16_t motor_rpm; // motor speed in rpm - uint8_t motor_pcb_temp; // motor pcb temp in C - uint8_t motor_stator_temp; // motor stator temp in C - uint8_t batt_charge_pct; // battery state of charge (0 to 100%) - float batt_voltage; // battery voltage in volts - float batt_current; // battery current in amps - uint16_t gps_speed; // gps speed in knots * 100 - uint16_t range_miles; // range in nautical miles * 10 - uint16_t range_minutes; // range in minutes (at current speed and current draw) - uint8_t temp_sw; // master PCB temp in C (close to motor power switches) - uint8_t temp_rp; // master PCB temp in C (close to reverse voltage protection) - uint32_t last_update_ms; // system time that system state was last updated - } _display_system_state; + // parameter var table + static const struct AP_Param::GroupInfo var_info[]; - // Display system setup - struct DisplaySystemSetup { - uint8_t flags; // 0 : battery config valid, all other bits unused - uint8_t motor_type; // motor type (0 or 3:Unknown, 1:Ultralight, 2:Cruise2, 4:Cruise4, 5:Travel503, 6:Travel1003, 7:Cruise10kW) - uint16_t motor_sw_version; // motor software version - uint16_t batt_capacity; // battery capacity in amp hours - uint8_t batt_charge_pct; // battery state of charge (0 to 100%) - uint8_t batt_type; // battery type (0:lead acid, 1:Lithium) - uint16_t master_sw_version; // master software version - } _display_system_setup; + // parameters for backends + AP_Torqeedo_Params _params[AP_TORQEEDO_MAX_INSTANCES]; - // Motor status - struct MotorStatus { - union PACKED { - struct { - uint8_t temp_limit_motor : 1; // 0, motor speed limited due to motor temp - uint8_t temp_limit_pcb : 1; // 1, motor speed limited tue to PCB temp - uint8_t emergency_stop : 1; // 2, motor in emergency stop (must be cleared by master) - uint8_t running : 1; // 3, motor running - uint8_t power_limit : 1; // 4, motor power limited - uint8_t low_voltage_limit : 1; // 5, motor speed limited because of low voltage - uint8_t tilt : 1; // 6, motor is tilted - uint8_t reserved7 : 1; // 7, unused (always zero) - } status_flags; - uint8_t status_flags_value; - }; - union PACKED { - struct { - uint8_t overcurrent : 1; // 0, motor stopped because of overcurrent - uint8_t blocked : 1; // 1, motor stopped because it is blocked - uint8_t overvoltage_static : 1; // 2, motor stopped because voltage too high - uint8_t undervoltage_static : 1; // 3, motor stopped because voltage too low - uint8_t overvoltage_current : 1; // 4, motor stopped because voltage spiked high - uint8_t undervoltage_current: 1; // 5, motor stopped because voltage spiked low - uint8_t overtemp_motor : 1; // 6, motor stopped because stator temp too high - uint8_t overtemp_pcb : 1; // 7, motor stopped because pcb temp too high - uint8_t timeout_rs485 : 1; // 8, motor stopped because Drive message not received for too long - uint8_t temp_sensor_error : 1; // 9, motor temp sensor is defective (motor will not stop) - uint8_t tilt : 1; // 10, motor stopped because it was tilted - uint8_t unused11to15 : 5; // 11 ~ 15 (always zero) - } error_flags; - uint16_t error_flags_value; - }; - } _motor_status; - uint32_t _last_send_motor_status_request_ms; // system time (in milliseconds) that last motor status request was sent +private: - // Motor params - struct MotorParam { - int16_t rpm; // motor rpm - uint16_t power; // motor power consumption in Watts - float voltage; // motor voltage in volts - float current; // motor current in amps - float pcb_temp; // pcb temp in C - float stator_temp; // stator temp in C - uint32_t last_update_ms;// system time that above values were updated - } _motor_param; - uint32_t _last_send_motor_param_request_ms; // system time (in milliseconds) that last motor param request was sent + // return pointer to backend given an instance number + AP_Torqeedo_Backend *get_instance(uint8_t instance) const; - // error reporting - DisplaySystemStateFlags _display_system_state_flags_prev; // backup of display system state flags - uint8_t _display_system_state_master_error_code_prev; // backup of display system state master_error_code - uint32_t _last_error_report_ms; // system time that flag changes were last reported (used to prevent spamming user) - MotorStatus _motor_status_prev; // backup of motor status static AP_Torqeedo *_singleton; - - // returns a human-readable string corresponding the passed-in - // master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) - // If no conversion is available then nullptr is returned - const char *map_master_error_code_to_string(uint8_t code) const; + AP_Torqeedo_Backend *_backends[AP_TORQEEDO_MAX_INSTANCES]; // pointers to instantiated backends }; namespace AP { diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Backend.cpp b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.cpp new file mode 100644 index 0000000000000..243f7cab23e8b --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.cpp @@ -0,0 +1,31 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Torqeedo_Backend.h" + +#if HAL_TORQEEDO_ENABLED + +#include +#include + +extern const AP_HAL::HAL& hal; + +// constructor +AP_Torqeedo_Backend::AP_Torqeedo_Backend(AP_Torqeedo_Params ¶ms, uint8_t instance) : + _params(params), + _instance(instance) +{} + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Backend.h b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.h new file mode 100644 index 0000000000000..fd56d0612aa91 --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Backend.h @@ -0,0 +1,84 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + This driver supports communicating with Torqeedo motors that implement the "TQ Bus" protocol + which includes the Ultralight, Cruise 2.0 R, Cruise 4.0 R, Travel 503, Travel 1003 and Cruise 10kW + + The autopilot should be connected either to the battery's tiller connector or directly to the motor + as described on the ArduPilot wiki. https://ardupilot.org/rover/docs/common-torqeedo.html + TQ Bus is a serial protocol over RS-485 meaning that a serial to RS-485 converter is required. + + Tiller connection: Autopilot <-> Battery (master) <-> Motor + Motor connection: Autopilot (master) <-> Motor + + Communication between the components is always initiated by the master with replies sent within 25ms + + Example "Remote (0x01)" reply message to allow tiller to control motor speed + Byte Field Definition Example Value Comments + --------------------------------------------------------------------------------- + byte 0 Header 0xAC + byte 1 TargetAddress 0x00 see MsgAddress enum + byte 2 Message ID 0x00 only master populates this. replies have this set to zero + byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid + byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 + byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) + byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) + byte 7 CRC-Maxim ---- CRC-Maxim value + byte 8 Footer 0xAD + + More details of the TQ Bus protocol are available from Torqeedo after signing an NDA. + */ + +#pragma once + +#include "AP_Torqeedo_config.h" + +#if HAL_TORQEEDO_ENABLED + +#include "AP_Torqeedo.h" +#include + +class AP_Torqeedo_Backend : public AP_ESC_Telem_Backend { +public: + AP_Torqeedo_Backend(AP_Torqeedo_Params ¶ms, uint8_t instance); + + // do not allow copies + CLASS_NO_COPY(AP_Torqeedo_Backend); + + // initialise driver + virtual void init() = 0; + + // returns true if communicating with the motor + virtual bool healthy() = 0; + + // clear motor errors + virtual void clear_motor_error() = 0; + + // get latest battery status info. returns true on success and populates arguments + virtual bool get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const WARN_IF_UNUSED = 0; + virtual bool get_batt_capacity_Ah(uint16_t &_hours) const = 0; + + protected: + + // parameter helper functions + AP_Torqeedo::ConnectionType get_type() const { return (AP_Torqeedo::ConnectionType)_params.type.get(); } + bool option_enabled(AP_Torqeedo::options opt) const { return ((uint16_t)_params.options.get() & (uint16_t)opt) != 0; } + + AP_Torqeedo_Params &_params; // parameters for this backend + uint8_t _instance; // this instance's number +}; + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Params.cpp b/libraries/AP_Torqeedo/AP_Torqeedo_Params.cpp new file mode 100644 index 0000000000000..2ded30ca844a3 --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Params.cpp @@ -0,0 +1,79 @@ +#include "AP_Torqeedo_Params.h" +#include + +// table of user settable parameters +const AP_Param::GroupInfo AP_Torqeedo_Params::var_info[] = { + + // @Param: TYPE + // @DisplayName: Torqeedo connection type + // @Description: Torqeedo connection type + // @Values: 0:Disabled, 1:Tiller, 2:Motor + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO_FLAGS("TYPE", 1, AP_Torqeedo_Params, type, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: ONOFF_PIN + // @DisplayName: Torqeedo ON/Off pin + // @Description: Pin number connected to Torqeedo's on/off pin. -1 to use serial port's RTS pin if available + // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("ONOFF_PIN", 2, AP_Torqeedo_Params, pin_onoff, -1), + + // @Param: DE_PIN + // @DisplayName: Torqeedo DE pin + // @Description: Pin number connected to RS485 to Serial converter's DE pin. -1 to use serial port's CTS pin if available + // @Values: -1:Disabled,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6 + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("DE_PIN", 3, AP_Torqeedo_Params, pin_de, -1), + + // @Param: OPTIONS + // @DisplayName: Torqeedo Options + // @Description: Torqeedo Options Bitmask + // @Bitmask: 0:Log,1:Send debug to GCS + // @User: Advanced + AP_GROUPINFO("OPTIONS", 4, AP_Torqeedo_Params, options, 1), + + // @Param: POWER + // @DisplayName: Torqeedo Motor Power + // @Description: Torqeedo motor power. Only applied when using motor connection type (e.g. TRQD_TYPE=2) + // @Units: % + // @Range: 0 100 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("POWER", 5, AP_Torqeedo_Params, motor_power, 100), + + // @Param: SLEW_TIME + // @DisplayName: Torqeedo Throttle Slew Time + // @Description: Torqeedo slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. Higher values cause a slower response, lower values cause a faster response. A value of zero disables the limit + // @Units: s + // @Range: 0 5 + // @Increment: 0.1 + // @User: Advanced + AP_GROUPINFO("SLEW_TIME", 6, AP_Torqeedo_Params, slew_time, 2.0), + + // @Param: DIR_DELAY + // @DisplayName: Torqeedo Direction Change Delay + // @Description: Torqeedo direction change delay. Output will remain at zero for this many seconds when transitioning between forward and backwards rotation + // @Units: s + // @Range: 0 5 + // @Increment: 0.1 + // @User: Advanced + AP_GROUPINFO("DIR_DELAY", 7, AP_Torqeedo_Params, dir_delay, 1.0), + + // @Param: SERVO_FN + // @DisplayName: Torqeedo Servo Output Function + // @Description: Torqeedo Servo Output Function + // @Values: 70:Throttle,73:ThrottleLeft,74:ThrottleRight + // @Increment: 0.1 + // @User: Advanced + AP_GROUPINFO("SERVO_FN", 8, AP_Torqeedo_Params, servo_fn, (int16_t)SRV_Channel::k_throttle), + + AP_GROUPEND +}; + +AP_Torqeedo_Params::AP_Torqeedo_Params(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_Params.h b/libraries/AP_Torqeedo/AP_Torqeedo_Params.h new file mode 100644 index 0000000000000..21211de32236e --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_Params.h @@ -0,0 +1,24 @@ +#pragma once + +#include +#include + +class AP_Torqeedo_Params { +public: + static const struct AP_Param::GroupInfo var_info[]; + + AP_Torqeedo_Params(void); + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Torqeedo_Params); + + // parameters + AP_Int8 type; // connector type used (0:disabled, 1:tiller connector, 2:motor connector) + AP_Int8 pin_onoff; // Pin number connected to Torqeedo's on/off pin. -1 to disable turning motor on/off from autopilot + AP_Int8 pin_de; // Pin number connected to RS485 to Serial converter's DE pin. -1 to disable sending commands to motor + AP_Int16 options; // options bitmask + AP_Int8 motor_power; // motor power (0 ~ 100). only applied when using motor connection + AP_Float slew_time; // slew rate specified as the minimum number of seconds required to increase the throttle from 0 to 100%. A value of zero disables the limit + AP_Float dir_delay; // direction change delay. output will remain at zero for this many seconds when transitioning between forward and backwards rotation + AP_Int16 servo_fn; // servo output function number +}; diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.cpp b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.cpp new file mode 100644 index 0000000000000..d90749d4f8a73 --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.cpp @@ -0,0 +1,1077 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Torqeedo_TQBus.h" + +#if HAL_TORQEEDO_ENABLED + +#include +#include +#include +#include +#include +#include +#include + +#define TORQEEDO_SERIAL_BAUD 19200 // communication is always at 19200 +#define TORQEEDO_PACKET_HEADER 0xAC // communication packet header +#define TORQEEDO_PACKET_FOOTER 0xAD // communication packet footer +#define TORQEEDO_PACKET_ESCAPE 0xAE // escape character for handling occurrences of header, footer and this escape bytes in original message +#define TORQEEDO_PACKET_ESCAPE_MASK 0x80 // byte after ESCAPE character should be XOR'd with this value +#define TORQEEDO_LOG_TRQD_INTERVAL_MS 5000// log TRQD message at this interval in milliseconds +#define TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS 100 // motor speed sent at 10hz if connected to motor +#define TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS 400 // motor status requested every 0.4sec if connected to motor +#define TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS 400 // motor param requested every 0.4sec if connected to motor +#define TORQEEDO_BATT_TIMEOUT_MS 5000 // battery info timeouts after 5 seconds +#define TORQEEDO_REPLY_TIMEOUT_MS 25 // stop waiting for replies after 25ms +#define TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS 10000 // errors reported to user at no less than once every 10 seconds + +extern const AP_HAL::HAL& hal; + +// initialise driver +void AP_Torqeedo_TQBus::init() +{ + // only init once + // Note: a race condition exists here if init is called multiple times quickly before thread_main has a chance to set _initialise + if (_initialised) { + return; + } + + // create background thread to process serial input and output + char thread_name[15]; + hal.util->snprintf(thread_name, sizeof(thread_name), "torqeedo%u", (unsigned)_instance); + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Torqeedo_TQBus::thread_main, void), thread_name, 2048, AP_HAL::Scheduler::PRIORITY_RCOUT, 1)) { + return; + } +} + +// returns true if communicating with the motor +bool AP_Torqeedo_TQBus::healthy() +{ + if (!_initialised) { + return false; + } + { + // healthy if both receive and send have occurred in the last 3 seconds + WITH_SEMAPHORE(_last_healthy_sem); + const uint32_t now_ms = AP_HAL::millis(); + return ((now_ms - _last_received_ms < 3000) && (now_ms - _last_send_motor_ms < 3000)); + } +} + +// initialise serial port and gpio pins (run from background thread) +bool AP_Torqeedo_TQBus::init_internals() +{ + // find serial driver and initialise + const AP_SerialManager &serial_manager = AP::serialmanager(); + _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Torqeedo, _instance); + if (_uart == nullptr) { + return false; + } + _uart->begin(TORQEEDO_SERIAL_BAUD); + _uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); + _uart->set_unbuffered_writes(true); + + // if using tiller connection set on/off pin for 0.5 sec to turn on battery + if (get_type() == AP_Torqeedo::ConnectionType::TYPE_TILLER) { + if (_params.pin_onoff > -1) { + hal.gpio->pinMode(_params.pin_onoff, HAL_GPIO_OUTPUT); + hal.gpio->write(_params.pin_onoff, 1); + hal.scheduler->delay(500); + hal.gpio->write(_params.pin_onoff, 0); + } else { + // use serial port's RTS pin to turn on battery + _uart->set_RTS_pin(true); + hal.scheduler->delay(500); + _uart->set_RTS_pin(false); + } + } + + // initialise RS485 DE pin (when high, allows send to motor) + if (_params.pin_de > -1) { + hal.gpio->pinMode(_params.pin_de, HAL_GPIO_OUTPUT); + hal.gpio->write(_params.pin_de, 0); + } else { + _uart->set_CTS_pin(false); + } + + return true; +} + +// consume incoming messages from motor, reply with latest motor speed +// runs in background thread +void AP_Torqeedo_TQBus::thread_main() +{ + // initialisation + if (!init_internals()) { + return; + } + _initialised = true; + + while (true) { + // 1ms loop delay + hal.scheduler->delay_microseconds(1000); + + // check if transmit pin should be unset + check_for_send_end(); + + // check for timeout waiting for reply + check_for_reply_timeout(); + + // parse incoming characters + uint32_t nbytes = MIN(_uart->available(), 1024U); + while (nbytes-- > 0) { + int16_t b = _uart->read(); + if (b >= 0 ) { + if (parse_byte((uint8_t)b)) { + // complete message received, parse it! + parse_message(); + // clear wait-for-reply because if we are waiting for a reply, this message must be it + set_reply_received(); + } + } + } + + // send motor speed + bool log_update = false; + if (safe_to_send()) { + uint32_t now_ms = AP_HAL::millis(); + + // if connected to motor + if (get_type() == AP_Torqeedo::ConnectionType::TYPE_MOTOR) { + if (now_ms - _last_send_motor_ms > TORQEEDO_SEND_MOTOR_SPEED_INTERVAL_MS) { + // send motor speed every 0.1sec + _send_motor_speed = true; + } else if (now_ms - _last_send_motor_status_request_ms > TORQEEDO_SEND_MOTOR_STATUS_REQUEST_INTERVAL_MS) { + // send request for motor status + send_motor_msg_request(MotorMsgId::STATUS); + _last_send_motor_status_request_ms = now_ms; + } else if (now_ms - _last_send_motor_param_request_ms > TORQEEDO_SEND_MOTOR_PARAM_REQUEST_INTERVAL_MS) { + // send request for motor params + send_motor_msg_request(MotorMsgId::PARAM); + _last_send_motor_param_request_ms = now_ms; + } + } + + // send motor speed + if (_send_motor_speed) { + send_motor_speed_cmd(); + _send_motor_speed = false; + log_update = true; + } + } + + // log high level status and motor speed + log_TRQD(log_update); + } +} + +// returns a human-readable string corresponding the passed-in +// master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) +// If no conversion is available then nullptr is returned +const char * AP_Torqeedo_TQBus::map_master_error_code_to_string(uint8_t code) const +{ + switch (code) { + case 2: + return "stator high temp"; + case 5: + return "propeller blocked"; + case 6: + return "motor low voltage"; + case 7: + return "motor high current"; + case 8: + return "pcb temp high"; + case 21: + return "tiller cal bad"; + case 22: + return "mag bad"; + case 23: + return "range incorrect"; + case 30: + return "motor comm error"; + case 32: + return "tiller comm error"; + case 33: + return "general comm error"; + case 41: + case 42: + return "charge voltage bad"; + case 43: + return "battery flat"; + case 45: + return "battery high current"; + case 46: + return "battery temp error"; + case 48: + return "charging temp error"; + } + + return nullptr; +} + +// report changes in error codes to user +void AP_Torqeedo_TQBus::report_error_codes() +{ + // skip reporting if we have already reported status very recently + const uint32_t now_ms = AP_HAL::millis(); + + // skip reporting if no changes in flags and already reported within 10 seconds + const bool flags_changed = (_display_system_state_flags_prev.value != _display_system_state.flags.value) || + (_display_system_state_master_error_code_prev != _display_system_state.master_error_code) || + (_motor_status_prev.status_flags_value != _motor_status.status_flags_value) || + (_motor_status_prev.error_flags_value != _motor_status.error_flags_value); + if (!flags_changed && ((now_ms - _last_error_report_ms) < TORQEEDO_ERROR_REPORT_INTERVAL_MAX_MS)) { + return; + } + + // report display system errors + const char* msg_prefix = "Torqeedo:"; + (void)msg_prefix; // sometimes unused when HAL_GCS_ENABLED is false + if (_display_system_state.flags.set_throttle_stop) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix); + } + if (_display_system_state.flags.temp_warning) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); + } + if (_display_system_state.flags.batt_nearly_empty) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", msg_prefix); + } + if (_display_system_state.master_error_code > 0) { + const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code); + if (error_string != nullptr) { + GCS_SEND_TEXT( + MAV_SEVERITY_CRITICAL, "%s err:%u %s", + msg_prefix, + _display_system_state.master_error_code, + error_string); + } else { + GCS_SEND_TEXT( + MAV_SEVERITY_CRITICAL, "%s err:%u", + msg_prefix, + _display_system_state.master_error_code); + } + } + + // report motor status errors + if (_motor_status.error_flags.overcurrent) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix); + } + if (_motor_status.error_flags.blocked) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s prop blocked", msg_prefix); + } + if (_motor_status.error_flags.overvoltage_static || _motor_status.error_flags.overvoltage_current) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high voltage", msg_prefix); + } + if (_motor_status.error_flags.undervoltage_static || _motor_status.error_flags.undervoltage_current) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s low voltage", msg_prefix); + } + if (_motor_status.error_flags.overtemp_motor || _motor_status.error_flags.overtemp_pcb) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); + } + if (_motor_status.error_flags.timeout_rs485) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s comm timeout", msg_prefix); + } + if (_motor_status.error_flags.temp_sensor_error) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s temp sensor err", msg_prefix); + } + if (_motor_status.error_flags.tilt) { + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix); + } + + // display OK if all errors cleared + const bool prev_errored = (_display_system_state_flags_prev.value != 0) || + (_display_system_state_master_error_code_prev != 0) || + (_motor_status_prev.error_flags_value != 0); + + const bool now_errored = (_display_system_state.flags.value != 0) || + (_display_system_state.master_error_code != 0) || + (_motor_status.error_flags_value != 0); + + if (!now_errored && prev_errored) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s OK", msg_prefix); + } + + // record change in state and reporting time + _display_system_state_flags_prev.value = _display_system_state.flags.value; + _display_system_state_master_error_code_prev = _display_system_state.master_error_code; + _motor_status_prev = _motor_status; + _last_error_report_ms = now_ms; +} + +// get latest battery status info. returns true on success and populates arguments +bool AP_Torqeedo_TQBus::get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const +{ + + // use battery info from display_system_state if available (tiller connection) + if ((AP_HAL::millis() - _display_system_state.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { + voltage = _display_system_state.batt_voltage; + current_amps = _display_system_state.batt_current; + temp_C = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); + pct_remaining = _display_system_state.batt_charge_pct; + return true; + } + + // use battery info from motor_param if available (motor connection) + if ((AP_HAL::millis() - _motor_param.last_update_ms) <= TORQEEDO_BATT_TIMEOUT_MS) { + voltage = _motor_param.voltage; + current_amps = _motor_param.current; + temp_C = MAX(_motor_param.pcb_temp, _motor_param.stator_temp); + pct_remaining = 0; // motor does not know percent remaining + return true; + } + + return false; +} + +// get battery capacity. returns true on success and populates argument +bool AP_Torqeedo_TQBus::get_batt_capacity_Ah(uint16_t &_hours) const +{ + if (_display_system_setup.batt_capacity == 0) { + return false; + } + amp_hours = _display_system_setup.batt_capacity; + return true; +} + +// process a single byte received on serial port +// return true if a complete message has been received (the message will be held in _received_buff) +bool AP_Torqeedo_TQBus::parse_byte(uint8_t b) +{ + bool complete_msg_received = false; + + switch (_parse_state) { + case ParseState::WAITING_FOR_HEADER: + if (b == TORQEEDO_PACKET_HEADER) { + _parse_state = ParseState::WAITING_FOR_FOOTER; + } + _received_buff_len = 0; + _parse_escape_received = false; + break; + case ParseState::WAITING_FOR_FOOTER: + if (b == TORQEEDO_PACKET_FOOTER) { + _parse_state = ParseState::WAITING_FOR_HEADER; + + // check message length + if (_received_buff_len == 0) { + _parse_error_count++; + break; + } + + // check crc + const uint8_t crc_expected = crc8_maxim(_received_buff, _received_buff_len-1); + if (_received_buff[_received_buff_len-1] != crc_expected) { + _parse_error_count++; + break; + } + _parse_success_count++; + { + // record time of successful receive for health reporting + WITH_SEMAPHORE(_last_healthy_sem); + _last_received_ms = AP_HAL::millis(); + } + complete_msg_received = true; + } else { + // escape character handling + if (_parse_escape_received) { + b ^= TORQEEDO_PACKET_ESCAPE_MASK; + _parse_escape_received = false; + } else if (b == TORQEEDO_PACKET_ESCAPE) { + // escape character received, record this and ignore this byte + _parse_escape_received = true; + break; + } + // add to buffer + _received_buff[_received_buff_len] = b; + _received_buff_len++; + if (_received_buff_len > TORQEEDO_MESSAGE_LEN_MAX) { + // message too long + _parse_state = ParseState::WAITING_FOR_HEADER; + _parse_error_count++; + } + } + break; + } + + return complete_msg_received; +} + +// process message held in _received_buff +void AP_Torqeedo_TQBus::parse_message() +{ + // message address (i.e. target of message) + const MsgAddress msg_addr = (MsgAddress)_received_buff[0]; + + // handle messages sent to "remote" (aka tiller) + if ((get_type() == AP_Torqeedo::ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::REMOTE1)) { + RemoteMsgId msg_id = (RemoteMsgId)_received_buff[1]; + if (msg_id == RemoteMsgId::REMOTE) { + // request received to send updated motor speed + _send_motor_speed = true; + } + return; + } + + // handle messages sent to Display + if ((get_type() == AP_Torqeedo::ConnectionType::TYPE_TILLER) && (msg_addr == MsgAddress::DISPLAY)) { + DisplayMsgId msg_id = (DisplayMsgId)_received_buff[1]; + switch (msg_id) { + case DisplayMsgId::SYSTEM_STATE : + if (_received_buff_len == 30) { + // fill in _display_system_state + _display_system_state.flags.value = UINT16_VALUE(_received_buff[2], _received_buff[3]); + _display_system_state.master_state = _received_buff[4]; // deprecated + _display_system_state.master_error_code = _received_buff[5]; + _display_system_state.motor_voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; + _display_system_state.motor_current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; + _display_system_state.motor_power = UINT16_VALUE(_received_buff[10], _received_buff[11]); + _display_system_state.motor_rpm = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]); + _display_system_state.motor_pcb_temp = _received_buff[14]; + _display_system_state.motor_stator_temp = _received_buff[15]; + _display_system_state.batt_charge_pct = _received_buff[16]; + _display_system_state.batt_voltage = UINT16_VALUE(_received_buff[17], _received_buff[18]) * 0.01; + _display_system_state.batt_current = UINT16_VALUE(_received_buff[19], _received_buff[20]) * 0.1; + _display_system_state.gps_speed = UINT16_VALUE(_received_buff[21], _received_buff[22]); + _display_system_state.range_miles = UINT16_VALUE(_received_buff[23], _received_buff[24]); + _display_system_state.range_minutes = UINT16_VALUE(_received_buff[25], _received_buff[26]); + _display_system_state.temp_sw = _received_buff[27]; + _display_system_state.temp_rp = _received_buff[28]; + _display_system_state.last_update_ms = AP_HAL::millis(); + + // update esc telem sent to ground station + const uint8_t esc_temp = MAX(_display_system_state.temp_sw, _display_system_state.temp_rp); + const uint8_t motor_temp = MAX(_display_system_state.motor_pcb_temp, _display_system_state.motor_stator_temp); + update_esc_telem(_display_system_state.motor_rpm, + _display_system_state.motor_voltage, + _display_system_state.motor_current, + esc_temp, + motor_temp); + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRST + // @Description: Torqeedo System State + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: F: Flags bitmask + // @Field: Err: Master error code + // @Field: MVolt: Motor voltage + // @Field: MCur: Motor current + // @Field: Pow: Motor power + // @Field: RPM: Motor RPM + // @Field: MTemp: Motor Temp (higher of pcb or stator) + // @Field: BPct: Battery charge percentage + // @Field: BVolt: Battery voltage + // @Field: BCur: Battery current + AP::logger().Write("TRST", "TimeUS,I,F,Err,MVolt,MCur,Pow,RPM,MTemp,BPct,BVolt,BCur", + "s#--vAWqO%vA", // units + "F---00000000", // multipliers + "QBHBffHhBBff", // formats + AP_HAL::micros64(), + _instance, + _display_system_state.flags.value, + _display_system_state.master_error_code, + _display_system_state.motor_voltage, + _display_system_state.motor_current, + _display_system_state.motor_power, + _display_system_state.motor_rpm, + motor_temp, + _display_system_state.batt_charge_pct, + _display_system_state.batt_voltage, + _display_system_state.batt_current); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRST i:%u, F:%u Err:%u MV:%4.1f MC:%4.1f P:%u MT:%d B%%:%d BV:%4.1f BC:%4.1f", + (unsigned)_instance, + (unsigned)_display_system_state.flags.value, + (unsigned)_display_system_state.master_error_code, + (double)_display_system_state.motor_voltage, + (double)_display_system_state.motor_current, + (unsigned)_display_system_state.motor_power, + (int)motor_temp, + (unsigned)_display_system_state.batt_charge_pct, + (double)_display_system_state.batt_voltage, + (double)_display_system_state.batt_current); + } + + // report any errors + report_error_codes(); + } else { + // unexpected length + _parse_error_count++; + } + break; + case DisplayMsgId::SYSTEM_SETUP: + if (_received_buff_len == 13) { + // fill in display system setup + _display_system_setup.flags = _received_buff[2]; + _display_system_setup.motor_type = _received_buff[3]; + _display_system_setup.motor_sw_version = UINT16_VALUE(_received_buff[4], _received_buff[5]); + _display_system_setup.batt_capacity = UINT16_VALUE(_received_buff[6], _received_buff[7]); + _display_system_setup.batt_charge_pct = _received_buff[8]; + _display_system_setup.batt_type = _received_buff[9]; + _display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]); + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRSE + // @Description: Torqeedo System Setup + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: Flag: Flags + // @Field: MotType: Motor type + // @Field: MotVer: Motor software version + // @Field: BattCap: Battery capacity + // @Field: BattPct: Battery charge percentage + // @Field: BattType: Battery type + // @Field: SwVer: Master software version + AP::logger().Write("TRSE", "TimeUS,I,Flag,MotType,MotVer,BattCap,BattPct,BattType,SwVer", + "s#---a%--", // units + "F----00--", // multipliers + "QBBBHHBBH", // formats + AP_HAL::micros64(), + _instance, + _display_system_setup.flags, + _display_system_setup.motor_type, + _display_system_setup.motor_sw_version, + _display_system_setup.batt_capacity, + _display_system_setup.batt_charge_pct, + _display_system_setup.batt_type, + _display_system_setup.master_sw_version); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRSE i:%u v:%u F:%u Mot:%u/%u Bat:%u/%u/%u%%", + (unsigned)_instance, + (unsigned)_display_system_setup.master_sw_version, + (unsigned)_display_system_setup.flags, + (unsigned)_display_system_setup.motor_type, + (unsigned)_display_system_setup.motor_sw_version, + (unsigned)_display_system_setup.batt_type, + (unsigned)_display_system_setup.batt_capacity, + (unsigned)_display_system_setup.batt_charge_pct); + } + } else { + // unexpected length + _parse_error_count++; + } + break; + default: + // ignore message + break; + } + return; + } + + // handle reply from motor + if ((get_type() == AP_Torqeedo::ConnectionType::TYPE_MOTOR) && (msg_addr == MsgAddress::BUS_MASTER)) { + // replies strangely do not return the msgid so we must have stored it + MotorMsgId msg_id = (MotorMsgId)_reply_msgid; + switch (msg_id) { + + case MotorMsgId::PARAM: + if (_received_buff_len == 15) { + _motor_param.rpm = (int16_t)UINT16_VALUE(_received_buff[2], _received_buff[3]); + _motor_param.power = UINT16_VALUE(_received_buff[4], _received_buff[5]); + _motor_param.voltage = UINT16_VALUE(_received_buff[6], _received_buff[7]) * 0.01; + _motor_param.current = UINT16_VALUE(_received_buff[8], _received_buff[9]) * 0.1; + _motor_param.pcb_temp = (int16_t)UINT16_VALUE(_received_buff[10], _received_buff[11]) * 0.1; + _motor_param.stator_temp = (int16_t)UINT16_VALUE(_received_buff[12], _received_buff[13]) * 0.1; + _motor_param.last_update_ms = AP_HAL::millis(); + + // update esc telem sent to ground station + update_esc_telem(_motor_param.rpm, + _motor_param.voltage, + _motor_param.current, + _motor_param.pcb_temp, // esc temp + _motor_param.stator_temp); // motor temp + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRMP + // @Description: Torqeedo Motor Param + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: RPM: Motor RPM + // @Field: Pow: Motor power + // @Field: Volt: Motor voltage + // @Field: Cur: Motor current + // @Field: ETemp: ESC Temp + // @Field: MTemp: Motor Temp + AP::logger().Write("TRMP", "TimeUS,I,RPM,Pow,Volt,Cur,ETemp,MTemp", + "s#qWvAOO", // units + "F-000000", // multipliers + "QBhHffff", // formats + AP_HAL::micros64(), + _instance, + _motor_param.rpm, + _motor_param.power, + _motor_param.voltage, + _motor_param.current, + _motor_param.pcb_temp, + _motor_param.stator_temp); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TRMP i:%u rpm:%d p:%u V:%4.1f C:%4.1f PT:%4.1f MT:%4.1f", + (unsigned)_instance, + (int)_motor_param.rpm, + (unsigned)_motor_param.power, + (double)_motor_param.voltage, + (double)_motor_param.current, + (double)_motor_param.pcb_temp, + (double)_motor_param.stator_temp); + } + } else { + // unexpected length + _parse_error_count++; + } + break; + + case MotorMsgId::STATUS: + if (_received_buff_len == 6) { + _motor_status.status_flags_value = _received_buff[2]; + _motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]); + +#if HAL_LOGGING_ENABLED + // log data + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRMS + // @Description: Torqeedo Motor Status + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: State: Motor status flags + // @Field: Err: Motor error flags + AP::logger().Write("TRMS", "TimeUS,I,State,Err", + "s#--", // units + "F---", // multipliers + "QBBH", // formats + AP_HAL::micros64(), + _instance, + _motor_status.status_flags_value, + _motor_status.error_flags_value); + } +#endif + + // send to GCS + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRMS i:%u S:%d Err:%d", + (unsigned)_instance, + _motor_status.status_flags_value, + _motor_status.error_flags_value); + } + + // report any errors + report_error_codes(); + } else { + // unexpected length + _parse_error_count++; + } + break; + + case MotorMsgId::INFO: + case MotorMsgId::DRIVE: + case MotorMsgId::CONFIG: + // we do not process these replies + break; + + default: + // ignore unknown messages + break; + } + } +} + +// set DE Serial CTS pin to enable sending commands to motor +void AP_Torqeedo_TQBus::send_start() +{ + // set gpio pin or serial port's CTS pin + if (_params.pin_de > -1) { + hal.gpio->write(_params.pin_de, 1); + } else { + _uart->set_CTS_pin(true); + } +} + +// check for timeout after sending and unset pin if required +void AP_Torqeedo_TQBus::check_for_send_end() +{ + if (_send_delay_us == 0) { + // not sending + return; + } + + if (AP_HAL::micros() - _send_start_us < _send_delay_us) { + // return if delay has not yet elapsed + return; + } + _send_delay_us = 0; + + // unset gpio or serial port's CTS pin + if (_params.pin_de > -1) { + hal.gpio->write(_params.pin_de, 0); + } else { + _uart->set_CTS_pin(false); + } +} + +// calculate delay require to allow bytes to be sent +uint32_t AP_Torqeedo_TQBus::calc_send_delay_us(uint8_t num_bytes) +{ + // baud rate of 19200 bits/sec + // total number of bits = 10 x num_bytes + // convert from seconds to micros by multiplying by 1,000,000 + // plus additional 300us safety margin + const uint32_t delay_us = 1e6 * num_bytes * 10 / TORQEEDO_SERIAL_BAUD + 300; + return delay_us; +} + +// record msgid of message to wait for and set timer for timeout handling +void AP_Torqeedo_TQBus::set_expected_reply_msgid(uint8_t msg_id) +{ + _reply_msgid = msg_id; + _reply_wait_start_ms = AP_HAL::millis(); +} + +// check for timeout waiting for reply message +void AP_Torqeedo_TQBus::check_for_reply_timeout() +{ + // return immediately if not waiting for reply + if (_reply_wait_start_ms == 0) { + return; + } + if (AP_HAL::millis() - _reply_wait_start_ms > TORQEEDO_REPLY_TIMEOUT_MS) { + _reply_wait_start_ms = 0; + _parse_error_count++; + } +} + +// mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply +void AP_Torqeedo_TQBus::set_reply_received() +{ + _reply_wait_start_ms = 0; +} + +// send a message to the motor with the specified message contents +// msg_contents should not include the header, footer or CRC +// returns true on success +bool AP_Torqeedo_TQBus::send_message(const uint8_t msg_contents[], uint8_t num_bytes) +{ + // buffer for outgoing message + uint8_t send_buff[TORQEEDO_MESSAGE_LEN_MAX]; + uint8_t send_buff_num_bytes = 0; + + // calculate crc + const uint8_t crc = crc8_maxim(msg_contents, num_bytes); + + // add header + send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_HEADER; + + // add contents + for (uint8_t i=0; i= ARRAY_SIZE(send_buff)) { + _parse_error_count++; + return false; + } + send_buff[send_buff_num_bytes++] = TORQEEDO_PACKET_FOOTER; + + // set send pin + send_start(); + + // write message + _uart->write(send_buff, send_buff_num_bytes); + + // record start and expected delay to send message + _send_start_us = AP_HAL::micros(); + _send_delay_us = calc_send_delay_us(send_buff_num_bytes); + + return true; +} + +// add a byte to a message buffer including adding the escape character (0xAE) if necessary +// this should only be used when adding the contents to the buffer, not the header and footer +// num_bytes is updated to the next free byte +bool AP_Torqeedo_TQBus::add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const +{ + bool escape_required = (byte_to_add == TORQEEDO_PACKET_HEADER || + byte_to_add == TORQEEDO_PACKET_FOOTER || + byte_to_add == TORQEEDO_PACKET_ESCAPE); + + // check if we have enough space + if (num_bytes + (escape_required ? 2 : 1) >= msg_buff_size) { + return false; + } + + // add byte + if (escape_required) { + msg_buff[num_bytes++] = TORQEEDO_PACKET_ESCAPE; + msg_buff[num_bytes++] = byte_to_add ^ TORQEEDO_PACKET_ESCAPE_MASK; + } else { + msg_buff[num_bytes++] = byte_to_add; + } + return true; +} + +// Example "Remote (0x01)" reply message to allow tiller to control motor speed +// Byte Field Definition Example Value Comments +// --------------------------------------------------------------------------------- +// byte 0 Header 0xAC +// byte 1 TargetAddress 0x00 see MsgAddress enum +// byte 2 Message ID 0x00 only master populates this. replies have this set to zero +// byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid +// byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 +// byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) +// byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) +// byte 7 CRC-Maxim ---- CRC-Maxim value +// byte 8 Footer 0xAD +// +// example message when rotating tiller handle forwards: "AC 00 00 05 00 00 ED 95 AD" (+237) +// example message when rotating tiller handle backwards: "AC 00 00 05 00 FF AE 2C 0C AD" (-82) + +// send a motor speed command as a value from -1000 to +1000 +// value is taken directly from SRV_Channel +// for tiller connection this sends the "Remote (0x01)" message +// for motor connection this sends the "Motor Drive (0x82)" message +void AP_Torqeedo_TQBus::send_motor_speed_cmd() +{ + // calculate desired motor speed + if (!hal.util->get_soft_armed()) { + _motor_speed_desired = 0; + } else { + // convert throttle output to motor output in range -1000 to +1000 + // ToDo: convert PWM output to motor output so that SERVOx_MIN, MAX and TRIM take effect + _motor_speed_desired = constrain_int16(SRV_Channels::get_output_norm((SRV_Channel::Aux_servo_function_t)_params.servo_fn.get()) * 1000.0, -1000, 1000); + } + + // updated limited motor speed + int16_t mot_speed_limited = calc_motor_speed_limited(_motor_speed_desired); + + // by default use tiller connection command + uint8_t mot_speed_cmd_buff[] = {(uint8_t)MsgAddress::BUS_MASTER, 0x0, 0x5, 0x0, HIGHBYTE(mot_speed_limited), LOWBYTE(mot_speed_limited)}; + + // update message if using motor connection + if (get_type() == AP_Torqeedo::ConnectionType::TYPE_MOTOR) { + const uint8_t motor_power = (uint8_t)constrain_int16(_params.motor_power, 0, 100); + mot_speed_cmd_buff[0] = (uint8_t)MsgAddress::MOTOR; + mot_speed_cmd_buff[1] = (uint8_t)MotorMsgId::DRIVE; + mot_speed_cmd_buff[2] = (mot_speed_limited == 0 ? 0 : 0x01) | (_motor_clear_error ? 0x04 : 0); // 1:enable motor, 2:fast off, 4:clear error + mot_speed_cmd_buff[3] = mot_speed_limited == 0 ? 0 : motor_power; // motor power from 0 to 100 + + // set expected reply message id + set_expected_reply_msgid((uint8_t)MotorMsgId::DRIVE); + + // reset motor clear error request + _motor_clear_error = false; + } + + // send a message + if (send_message(mot_speed_cmd_buff, ARRAY_SIZE(mot_speed_cmd_buff))) { + // record time of send for health reporting + WITH_SEMAPHORE(_last_healthy_sem); + _last_send_motor_ms = AP_HAL::millis(); + } +} + +// send request to motor to reply with a particular message +// msg_id can be INFO, STATUS or PARAM +void AP_Torqeedo_TQBus::send_motor_msg_request(MotorMsgId msg_id) +{ + // prepare message + uint8_t mot_status_request_buff[] = {(uint8_t)MsgAddress::MOTOR, (uint8_t)msg_id}; + + // send a message + if (send_message(mot_status_request_buff, ARRAY_SIZE(mot_status_request_buff))) { + // record waiting for reply + set_expected_reply_msgid((uint8_t)msg_id); + } +} + +// calculate the limited motor speed that is sent to the motors +// desired_motor_speed argument and returned value are in the range -1000 to 1000 +int16_t AP_Torqeedo_TQBus::calc_motor_speed_limited(int16_t desired_motor_speed) +{ + const uint32_t now_ms = AP_HAL::millis(); + + // update dir_limit flag for forward-reverse transition delay + const bool dir_delay_active = is_positive(_params.dir_delay); + if (!dir_delay_active) { + // allow movement in either direction + _dir_limit = 0; + } else { + // by default limit motor direction to previous iteration's direction + if (is_positive(_motor_speed_limited)) { + _dir_limit = 1; + } else if (is_negative(_motor_speed_limited)) { + _dir_limit = -1; + } else { + // motor speed is zero + if ((_motor_speed_zero_ms != 0) && ((now_ms - _motor_speed_zero_ms) > (_params.dir_delay * 1000))) { + // delay has passed so allow movement in either direction + _dir_limit = 0; + _motor_speed_zero_ms = 0; + } + } + } + + // calculate upper and lower limits for forward-reverse transition delay + int16_t lower_limit = -1000; + int16_t upper_limit = 1000; + if (_dir_limit < 0) { + upper_limit = 0; + } + if (_dir_limit > 0) { + lower_limit = 0; + } + + // calculate dt since last update + float dt = (now_ms - _motor_speed_limited_ms) * 0.001f; + if (dt > 1.0) { + // after a long delay limit motor output to zero to avoid sudden starts + lower_limit = 0; + upper_limit = 0; + } + _motor_speed_limited_ms = now_ms; + + // apply slew limit + if (_params.slew_time > 0) { + const float chg_max = 1000.0 * dt / _params.slew_time; + _motor_speed_limited = constrain_float(desired_motor_speed, _motor_speed_limited - chg_max, _motor_speed_limited + chg_max); + } else { + // no slew limit + _motor_speed_limited = desired_motor_speed; + } + + // apply upper and lower limits + _motor_speed_limited = constrain_float(_motor_speed_limited, lower_limit, upper_limit); + + // record time motor speed becomes zero + if (is_zero(_motor_speed_limited)) { + if (_motor_speed_zero_ms == 0) { + _motor_speed_zero_ms = now_ms; + } + } else { + // clear timer + _motor_speed_zero_ms = 0; + } + + return (int16_t)_motor_speed_limited; +} + +// output logging and debug messages (if required) +// force_logging should be true if caller wants to ensure the latest status is logged +void AP_Torqeedo_TQBus::log_TRQD(bool force_logging) +{ + // exit immediately if logging and debug options are not set + if (!option_enabled(AP_Torqeedo::options::LOG) && option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + return; + } + + // return if not enough time has passed since last output + const uint32_t now_ms = AP_HAL::millis(); + if (!force_logging && (now_ms - _last_log_TRQD_ms < TORQEEDO_LOG_TRQD_INTERVAL_MS)) { + return; + } + _last_log_TRQD_ms = now_ms; + +#if HAL_LOGGING_ENABLED || HAL_GCS_ENABLED + const bool health = healthy(); + int16_t actual_motor_speed = get_motor_speed_limited(); + +#if HAL_LOGGING_ENABLED + if (option_enabled(AP_Torqeedo::options::LOG)) { + // @LoggerMessage: TRQD + // @Description: Torqeedo Status + // @Field: TimeUS: Time since system startup + // @Field: I: instance + // @Field: Health: Health + // @Field: DesMotSpeed: Desired Motor Speed (-1000 to 1000) + // @Field: MotSpeed: Motor Speed (-1000 to 1000) + // @Field: SuccCnt: Success Count + // @Field: ErrCnt: Error Count + AP::logger().Write("TRQD", "TimeUS,I,Health,DesMotSpeed,MotSpeed,SuccCnt,ErrCnt", + "s#-----", // units + "F------", // multipliers + "QBBhhII", // formats + AP_HAL::micros64(), + _instance, + health, + _motor_speed_desired, + actual_motor_speed, + _parse_success_count, + _parse_error_count); + } +#endif + + if (option_enabled(AP_Torqeedo::options::DEBUG_TO_GCS)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD i:%u h:%u dspd:%d spd:%d succ:%ld err:%ld", + (unsigned)_instance, + (unsigned)health, + (int)_motor_speed_desired, + (int)actual_motor_speed, + (unsigned long)_parse_success_count, + (unsigned long)_parse_error_count); + } +#endif // HAL_LOGGING_ENABLED || HAL_GCS_ENABLED +} + +// send ESC telemetry +void AP_Torqeedo_TQBus::update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC) +{ +#if HAL_WITH_ESC_TELEM + // find servo output channel + uint8_t telem_esc_index = 0; + IGNORE_RETURN(SRV_Channels::find_channel((SRV_Channel::Aux_servo_function_t)_params.servo_fn.get(), telem_esc_index)); + + // fill in telemetry data structure + AP_ESC_Telem_Backend::TelemetryData telem_dat {}; + telem_dat.temperature_cdeg = esc_tempC * 100; // temperature in centi-degrees + telem_dat.voltage = voltage; // voltage in volts + telem_dat.current = current_amps; // current in amps + telem_dat.motor_temp_cdeg = motor_tempC * 100; // motor temperature in centi-degrees + + // send telem and rpm data + update_telem_data(telem_esc_index, telem_dat, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | + AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | + AP_ESC_Telem_Backend::TelemetryType::CURRENT | + AP_ESC_Telem_Backend::TelemetryType::VOLTAGE); + + update_rpm(telem_esc_index, rpm); +#endif +} + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.h b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.h new file mode 100644 index 0000000000000..1b8dfc560a622 --- /dev/null +++ b/libraries/AP_Torqeedo/AP_Torqeedo_TQBus.h @@ -0,0 +1,332 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +/* + This driver supports communicating with Torqeedo motors that implement the "TQ Bus" protocol + which includes the Ultralight, Cruise 2.0 R, Cruise 4.0 R, Travel 503, Travel 1003 and Cruise 10kW + + The autopilot should be connected either to the battery's tiller connector or directly to the motor + as described on the ArduPilot wiki. https://ardupilot.org/rover/docs/common-torqeedo.html + TQ Bus is a serial protocol over RS-485 meaning that a serial to RS-485 converter is required. + + Tiller connection: Autopilot <-> Battery (master) <-> Motor + Motor connection: Autopilot (master) <-> Motor + + Communication between the components is always initiated by the master with replies sent within 25ms + + Example "Remote (0x01)" reply message to allow tiller to control motor speed + Byte Field Definition Example Value Comments + --------------------------------------------------------------------------------- + byte 0 Header 0xAC + byte 1 TargetAddress 0x00 see MsgAddress enum + byte 2 Message ID 0x00 only master populates this. replies have this set to zero + byte 3 Flags 0x05 bit0=pin present, bit2=motor speed valid + byte 4 Status 0x00 0x20 if byte3=4, 0x0 is byte3=5 + byte 5 Motor Speed MSB ---- Motor Speed MSB (-1000 to +1000) + byte 6 Motor Speed LSB ---- Motor Speed LSB (-1000 to +1000) + byte 7 CRC-Maxim ---- CRC-Maxim value + byte 8 Footer 0xAD + + More details of the TQ Bus protocol are available from Torqeedo after signing an NDA. + */ + +#pragma once + +#include "AP_Torqeedo_config.h" + +#if HAL_TORQEEDO_ENABLED + +#include "AP_Torqeedo_Backend.h" + +#define TORQEEDO_MESSAGE_LEN_MAX 35 // messages are no more than 35 bytes + +class AP_Torqeedo_TQBus : public AP_Torqeedo_Backend { +public: + + // constructor + using AP_Torqeedo_Backend::AP_Torqeedo_Backend; + + CLASS_NO_COPY(AP_Torqeedo_TQBus); + + // initialise driver + void init() override; + + // returns true if communicating with the motor + bool healthy() override; + + // clear motor errors + void clear_motor_error() override { _motor_clear_error = true; } + + // get latest battery status info. returns true on success and populates arguments + bool get_batt_info(float &voltage, float ¤t_amps, float &temp_C, uint8_t &pct_remaining) const override; + bool get_batt_capacity_Ah(uint16_t &_hours) const override; + +private: + + // consume incoming messages from motor, reply with latest motor speed + // runs in background thread + void thread_main(); + + // report changes in error codes to user + void report_error_codes(); + + // message addresses + enum class MsgAddress : uint8_t { + BUS_MASTER = 0x00, + REMOTE1 = 0x14, + DISPLAY = 0x20, + MOTOR = 0x30, + BATTERY = 0x80 + }; + + // Remote specific message ids + enum class RemoteMsgId : uint8_t { + INFO = 0x00, + REMOTE = 0x01, + SETUP = 0x02 + }; + + // Display specific message ids + enum class DisplayMsgId : uint8_t { + INFO = 0x00, + SYSTEM_STATE = 0x41, + SYSTEM_SETUP = 0x42 + }; + + // Motor specific message ids + enum class MotorMsgId : uint8_t { + INFO = 0x00, + STATUS = 0x01, + PARAM = 0x03, + CONFIG = 0x04, + DRIVE = 0x82 + }; + + enum class ParseState { + WAITING_FOR_HEADER = 0, + WAITING_FOR_FOOTER, + }; + + // initialise serial port and gpio pins (run from background thread) + // returns true on success + bool init_internals(); + + // process a single byte received on serial port + // return true if a complete message has been received (the message will be held in _received_buff) + bool parse_byte(uint8_t b); + + // process message held in _received_buff + void parse_message(); + + // returns true if it is safe to send a message + bool safe_to_send() const { return ((_send_delay_us == 0) && (_reply_wait_start_ms == 0)); } + + // set pin to enable sending a message + void send_start(); + + // check for timeout after sending a message and unset pin if required + void check_for_send_end(); + + // calculate delay required to allow message to be completely sent + uint32_t calc_send_delay_us(uint8_t num_bytes); + + // record msgid of message to wait for and set timer for reply timeout handling + void set_expected_reply_msgid(uint8_t msg_id); + + // check for timeout waiting for reply + void check_for_reply_timeout(); + + // mark reply received. should be called whenever a message is received regardless of whether we are actually waiting for a reply + void set_reply_received(); + + // send a message to the motor with the specified message contents + // msg_contents should not include the header, footer or CRC + // returns true on success + bool send_message(const uint8_t msg_contents[], uint8_t num_bytes); + + // add a byte to a message buffer including adding the escape character (0xAE) if necessary + // this should only be used when adding the contents to the buffer, not the header and footer + // num_bytes is updated to the next free byte + bool add_byte_to_message(uint8_t byte_to_add, uint8_t msg_buff[], uint8_t msg_buff_size, uint8_t &num_bytes) const; + + // send a motor speed command as a value from -1000 to +1000 + // value is taken directly from SRV_Channel + void send_motor_speed_cmd(); + + // send request to motor to reply with a particular message + // msg_id can be INFO, STATUS or PARAM + void send_motor_msg_request(MotorMsgId msg_id); + + // calculate the limited motor speed that is sent to the motors + // desired_motor_speed argument and returned value are in the range -1000 to 1000 + int16_t calc_motor_speed_limited(int16_t desired_motor_speed); + int16_t get_motor_speed_limited() const { return (int16_t)_motor_speed_limited; } + + // log TRQD message which holds high level status and latest desired motors peed + // force_logging should be true to immediately write log bypassing timing check to avoid spamming + void log_TRQD(bool force_logging); + + // send ESC telemetry + void update_esc_telem(float rpm, float voltage, float current_amps, float esc_tempC, float motor_tempC); + + // members + AP_HAL::UARTDriver *_uart; // serial port to communicate with motor + bool _initialised; // true once driver has been initialised + bool _send_motor_speed; // true if motor speed should be sent at next opportunity + int16_t _motor_speed_desired; // desired motor speed (set from within update method) + uint32_t _last_send_motor_ms; // system time (in millis) last motor speed command was sent (used for health reporting) + bool _motor_clear_error; // true if the motor error should be cleared (sent in "Drive" message) + uint32_t _send_start_us; // system time (in micros) when last message started being sent (used for timing to unset DE pin) + uint32_t _send_delay_us; // delay (in micros) to allow bytes to be sent after which pin can be unset. 0 if not delaying + + // motor speed limit variables + float _motor_speed_limited; // limited desired motor speed. this value is actually sent to the motor + uint32_t _motor_speed_limited_ms; // system time that _motor_speed_limited was last updated + int8_t _dir_limit; // acceptable directions for output to motor (+1 = positive OK, -1 = negative OK, 0 = either positive or negative OK) + uint32_t _motor_speed_zero_ms; // system time that _motor_speed_limited reached zero. 0 if currently not zero + + // health reporting + HAL_Semaphore _last_healthy_sem;// semaphore protecting reading and updating of _last_send_motor_ms and _last_received_ms + uint32_t _last_log_TRQD_ms; // system time (in millis) that TRQD was last logged + + // message parsing members + ParseState _parse_state; // current state of parsing + bool _parse_escape_received; // true if the escape character has been received so we must XOR the next byte + uint32_t _parse_error_count; // total number of parsing errors (for reporting) + uint32_t _parse_success_count; // number of messages successfully parsed (for reporting) + uint8_t _received_buff[TORQEEDO_MESSAGE_LEN_MAX]; // characters received + uint8_t _received_buff_len; // number of characters received + uint32_t _last_received_ms; // system time (in millis) that a message was successfully parsed (for health reporting) + + // reply message handling + uint8_t _reply_msgid; // replies expected msgid (reply often does not specify the msgid so we must record it) + uint32_t _reply_wait_start_ms; // system time that we started waiting for a reply message + + // Display system state flags + typedef union PACKED { + struct { + uint8_t set_throttle_stop : 1; // 0, warning that user must set throttle to stop before motor can run + uint8_t setup_allowed : 1; // 1, remote is allowed to enter setup mode + uint8_t in_charge : 1; // 2, master is in charging state + uint8_t in_setup : 1; // 3, master is in setup state + uint8_t bank_available : 1; // 4 + uint8_t no_menu : 1; // 5 + uint8_t menu_off : 1; // 6 + uint8_t reserved7 : 1; // 7, unused + uint8_t temp_warning : 1; // 8, motor or battery temp warning + uint8_t batt_charge_valid : 1; // 9, battery charge valid + uint8_t batt_nearly_empty : 1; // 10, battery nearly empty + uint8_t batt_charging : 1; // 11, battery charging + uint8_t gps_searching : 1; // 12, gps searching for satellites + uint8_t gps_speed_valid : 1; // 13, gps speed is valid + uint8_t range_miles_valid : 1; // 14, range (in miles) is valid + uint8_t range_minutes_valid : 1; // 15, range (in minutes) is valid + }; + uint16_t value; + } DisplaySystemStateFlags; + + // Display system state + struct DisplaySystemState { + DisplaySystemStateFlags flags; // flags, see above for individual bit definitions + uint8_t master_state; // deprecated + uint8_t master_error_code; // error code (0=no error) + float motor_voltage; // motor voltage in volts + float motor_current; // motor current in amps + uint16_t motor_power; // motor power in watts + int16_t motor_rpm; // motor speed in rpm + uint8_t motor_pcb_temp; // motor pcb temp in C + uint8_t motor_stator_temp; // motor stator temp in C + uint8_t batt_charge_pct; // battery state of charge (0 to 100%) + float batt_voltage; // battery voltage in volts + float batt_current; // battery current in amps + uint16_t gps_speed; // gps speed in knots * 100 + uint16_t range_miles; // range in nautical miles * 10 + uint16_t range_minutes; // range in minutes (at current speed and current draw) + uint8_t temp_sw; // master PCB temp in C (close to motor power switches) + uint8_t temp_rp; // master PCB temp in C (close to reverse voltage protection) + uint32_t last_update_ms; // system time that system state was last updated + } _display_system_state; + + // Display system setup + struct DisplaySystemSetup { + uint8_t flags; // 0 : battery config valid, all other bits unused + uint8_t motor_type; // motor type (0 or 3:Unknown, 1:Ultralight, 2:Cruise2, 4:Cruise4, 5:Travel503, 6:Travel1003, 7:Cruise10kW) + uint16_t motor_sw_version; // motor software version + uint16_t batt_capacity; // battery capacity in amp hours + uint8_t batt_charge_pct; // battery state of charge (0 to 100%) + uint8_t batt_type; // battery type (0:lead acid, 1:Lithium) + uint16_t master_sw_version; // master software version + } _display_system_setup; + + // Motor status + struct MotorStatus { + union PACKED { + struct { + uint8_t temp_limit_motor : 1; // 0, motor speed limited due to motor temp + uint8_t temp_limit_pcb : 1; // 1, motor speed limited tue to PCB temp + uint8_t emergency_stop : 1; // 2, motor in emergency stop (must be cleared by master) + uint8_t running : 1; // 3, motor running + uint8_t power_limit : 1; // 4, motor power limited + uint8_t low_voltage_limit : 1; // 5, motor speed limited because of low voltage + uint8_t tilt : 1; // 6, motor is tilted + uint8_t reserved7 : 1; // 7, unused (always zero) + } status_flags; + uint8_t status_flags_value; + }; + union PACKED { + struct { + uint8_t overcurrent : 1; // 0, motor stopped because of overcurrent + uint8_t blocked : 1; // 1, motor stopped because it is blocked + uint8_t overvoltage_static : 1; // 2, motor stopped because voltage too high + uint8_t undervoltage_static : 1; // 3, motor stopped because voltage too low + uint8_t overvoltage_current : 1; // 4, motor stopped because voltage spiked high + uint8_t undervoltage_current: 1; // 5, motor stopped because voltage spiked low + uint8_t overtemp_motor : 1; // 6, motor stopped because stator temp too high + uint8_t overtemp_pcb : 1; // 7, motor stopped because pcb temp too high + uint8_t timeout_rs485 : 1; // 8, motor stopped because Drive message not received for too long + uint8_t temp_sensor_error : 1; // 9, motor temp sensor is defective (motor will not stop) + uint8_t tilt : 1; // 10, motor stopped because it was tilted + uint8_t unused11to15 : 5; // 11 ~ 15 (always zero) + } error_flags; + uint16_t error_flags_value; + }; + } _motor_status; + uint32_t _last_send_motor_status_request_ms; // system time (in milliseconds) that last motor status request was sent + + // Motor params + struct MotorParam { + int16_t rpm; // motor rpm + uint16_t power; // motor power consumption in Watts + float voltage; // motor voltage in volts + float current; // motor current in amps + float pcb_temp; // pcb temp in C + float stator_temp; // stator temp in C + uint32_t last_update_ms;// system time that above values were updated + } _motor_param; + uint32_t _last_send_motor_param_request_ms; // system time (in milliseconds) that last motor param request was sent + + // error reporting + DisplaySystemStateFlags _display_system_state_flags_prev; // backup of display system state flags + uint8_t _display_system_state_master_error_code_prev; // backup of display system state master_error_code + uint32_t _last_error_report_ms; // system time that flag changes were last reported (used to prevent spamming user) + MotorStatus _motor_status_prev; // backup of motor status + + // returns a human-readable string corresponding the passed-in + // master error code (see page 93 of https://media.torqeedo.com/downloads/manuals/torqeedo-Travel-manual-DE-EN.pdf) + // If no conversion is available then nullptr is returned + const char *map_master_error_code_to_string(uint8_t code) const; +}; + +#endif // HAL_TORQEEDO_ENABLED diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 829383dd310e4..b05851bdfe7f8 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -367,9 +367,11 @@ void AP_Vehicle::setup() networking.init(); #endif +#if AP_SCHEDULER_ENABLED // Register scheduler_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay hal.scheduler->register_delay_callback(scheduler_delay_callback, 5); +#endif #if HAL_MSP_ENABLED // call MSP init before init_ardupilot to allow for MSP sensors @@ -431,7 +433,11 @@ void AP_Vehicle::setup() // gyro FFT needs to be initialized really late #if HAL_GYROFFT_ENABLED +#if AP_SCHEDULER_ENABLED gyro_fft.init(AP::scheduler().get_loop_rate_hz()); +#else + gyro_fft.init(1000); +#endif #endif #if HAL_RUNCAM_ENABLED runcam.init(); @@ -520,8 +526,13 @@ void AP_Vehicle::setup() void AP_Vehicle::loop() { +#if AP_SCHEDULER_ENABLED scheduler.loop(); G_Dt = scheduler.get_loop_period_s(); +#else + hal.scheduler->delay(1); + G_Dt = 0.001; +#endif if (!done_safety_init) { /* @@ -548,6 +559,7 @@ void AP_Vehicle::loop() } } +#if AP_SCHEDULER_ENABLED /* scheduler table - all regular tasks apart from the fast_loop() should be listed here. @@ -708,6 +720,7 @@ void AP_Vehicle::scheduler_delay_callback() logger.EnableWrites(true); #endif } +#endif // AP_SCHEDULER_ENABLED // if there's been a watchdog reset, notify the world via a statustext: void AP_Vehicle::send_watchdog_reset_statustext() diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 0ea6a802ca665..8b22c9395d73d 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -127,10 +127,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // parameters for example. void notify_no_such_mode(uint8_t mode_number); +#if AP_SCHEDULER_ENABLED void get_common_scheduler_tasks(const AP_Scheduler::Task*& tasks, uint8_t& num_tasks); // implementations *MUST* fill in all passed-in fields or we get // Valgrind errors -#if AP_SCHEDULER_ENABLED virtual void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) = 0; #endif @@ -310,8 +310,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_CANManager can_mgr; #endif +#if AP_SCHEDULER_ENABLED // main loop scheduler AP_Scheduler scheduler; +#endif // IMU variables // Integration time; time last loop took to run @@ -461,7 +463,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #endif static const struct AP_Param::GroupInfo var_info[]; +#if AP_SCHEDULER_ENABLED static const struct AP_Scheduler::Task scheduler_tasks[]; +#endif #if OSD_ENABLED void publish_osd_info(); @@ -495,8 +499,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { private: +#if AP_SCHEDULER_ENABLED // delay() callback that processing MAVLink packets static void scheduler_delay_callback(); +#endif // if there's been a watchdog reset, notify the world via a // statustext: diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index a710de35daa7c..f3329715913f2 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -515,7 +515,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/Filter/NotchFilter.cpp b/libraries/Filter/NotchFilter.cpp index dbbec6f80a802..29a531ef009f6 100644 --- a/libraries/Filter/NotchFilter.cpp +++ b/libraries/Filter/NotchFilter.cpp @@ -19,6 +19,7 @@ #endif #include "NotchFilter.h" +#include const static float NOTCH_MAX_SLEW = 0.05f; const static float NOTCH_MAX_SLEW_LOWER = 1.0f - NOTCH_MAX_SLEW; @@ -45,13 +46,11 @@ template void NotchFilter::init(float sample_freq_hz, float center_freq_hz, float bandwidth_hz, float attenuation_dB) { // check center frequency is in the allowable range + initialised = false; if ((center_freq_hz > 0.5 * bandwidth_hz) && (center_freq_hz < 0.5 * sample_freq_hz)) { float A, Q; - initialised = false; // force center frequency change calculate_A_and_Q(center_freq_hz, bandwidth_hz, attenuation_dB, A, Q); init_with_A_and_Q(sample_freq_hz, center_freq_hz, A, Q); - } else { - initialised = false; } } @@ -135,6 +134,15 @@ void NotchFilter::reset() need_reset = true; } +#if HAL_LOGGING_ENABLED +// return the frequency to log for the notch +template +float NotchFilter::logging_frequency() const +{ + return initialised ? _center_freq_hz : AP::logger().quiet_nanf(); +} +#endif + /* instantiate template classes */ diff --git a/libraries/Filter/NotchFilter.h b/libraries/Filter/NotchFilter.h index 9f2e49c66acb6..811f7800fccf5 100644 --- a/libraries/Filter/NotchFilter.h +++ b/libraries/Filter/NotchFilter.h @@ -49,9 +49,7 @@ class NotchFilter { } // return the frequency to log for the notch - float logging_frequency(void) const { - return initialised?_center_freq_hz:0; - } + float logging_frequency(void) const; protected: diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index 609b91a17c017..9539ded757083 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -376,9 +376,11 @@ bool GCS::out_of_time() const return false; } +#if AP_SCHEDULER_ENABLED if (min_loop_time_remaining_for_message_send_us() <= AP::scheduler().time_available_usec()) { return false; } +#endif return true; } diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index a6231ed988b5c..148757e0b49f0 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -522,12 +522,14 @@ class GCS_MAVLINK void handle_set_mode(const mavlink_message_t &msg); void handle_command_int(const mavlink_message_t &msg); - MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_int_external_position_estimate(const mavlink_command_int_t &packet); +#if AP_HOME_ENABLED + MAV_RESULT handle_command_do_set_home(const mavlink_command_int_t &packet); bool set_home_to_current_location(bool lock); bool set_home(const Location& loc, bool lock); +#endif #if AP_ARMING_ENABLED virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 3b81e551adbe4..fadf622bdc21e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -77,7 +77,7 @@ #include -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED #include #include #endif @@ -3626,7 +3626,7 @@ void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t &msg) */ void GCS_MAVLINK::handle_data_packet(const mavlink_message_t &msg) { -#if HAL_RCINPUT_WITH_AP_RADIO +#if AP_RADIO_ENABLED mavlink_data96_t m; mavlink_msg_data96_decode(&msg, &m); switch (m.type) { @@ -5066,6 +5066,7 @@ void GCS_MAVLINK::handle_landing_target(const mavlink_message_t &msg) } +#if AP_HOME_ENABLED bool GCS_MAVLINK::set_home_to_current_location(bool _lock) { #if AP_VEHICLE_ENABLED @@ -5082,7 +5083,9 @@ bool GCS_MAVLINK::set_home(const Location& loc, bool _lock) { return false; #endif } +#endif // AP_HOME_ENABLED +#if AP_HOME_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &packet) { if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) { @@ -5105,6 +5108,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t & } return MAV_RESULT_ACCEPTED; } +#endif // AP_HOME_ENABLED #if AP_AHRS_POSITION_RESET_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavlink_command_int_t &packet) @@ -5309,8 +5313,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p send_banner(); return MAV_RESULT_ACCEPTED; +#if AP_HOME_ENABLED case MAV_CMD_DO_SET_HOME: return handle_command_do_set_home(packet); +#endif + #if AP_AHRS_POSITION_RESET_ENABLED case MAV_CMD_EXTERNAL_POSITION_ESTIMATE: return handle_command_int_external_position_estimate(packet); @@ -6760,14 +6767,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/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index d29faaa7f6e8a..bf42339d124a6 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -73,6 +73,8 @@ void MissionItemProtocol::handle_mission_count( // the upload count may have changed; free resources and // allocate them again: free_upload_resources(); + receiving = false; + link = nullptr; } if (packet.count > max_items()) { @@ -218,6 +220,19 @@ void MissionItemProtocol::handle_mission_write_partial_list(GCS_MAVLINK &_link, const mavlink_message_t &msg, const mavlink_mission_write_partial_list_t &packet) { + if (!mavlink2_requirement_met(_link, msg)) { + return; + } + + if (receiving) { + // someone is already uploading a mission. Deny ability to + // write a partial list here as they might be trying to + // overwrite a subset of the waypoints which the current + // transfer is uploading, and that may lead to storing a whole + // bunch of empty items. + send_mission_ack(_link, msg, MAV_MISSION_DENIED); + return; + } // start waypoint receiving if ((unsigned)packet.start_index > item_count() || diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 2790c692e747b..bc69002ccef39 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -37,6 +37,7 @@ #include #include #include +#include using namespace SITL; @@ -176,16 +177,18 @@ void Aircraft::update_position(void) pos_home.x, pos_home.y, pos_home.z); #endif - uint32_t now = AP_HAL::millis(); - if (now - last_one_hz_ms >= 1000) { - // shift origin of position at 1Hz to current location - // this prevents sperical errors building up in the GPS data - last_one_hz_ms = now; - Vector2d diffNE = origin.get_distance_NE_double(location); - position.xy() -= diffNE; - smoothing.position.xy() -= diffNE; - origin.lat = location.lat; - origin.lng = location.lng; + if (!disable_origin_movement) { + uint32_t now = AP_HAL::millis(); + if (now - last_one_hz_ms >= 1000) { + // shift origin of position at 1Hz to current location + // this prevents sperical errors building up in the GPS data + last_one_hz_ms = now; + Vector2d diffNE = origin.get_distance_NE_double(location); + position.xy() -= diffNE; + smoothing.position.xy() -= diffNE; + origin.lat = location.lat; + origin.lng = location.lng; + } } } @@ -619,8 +622,18 @@ void Aircraft::update_model(const struct sitl_input &input) */ void Aircraft::update_dynamics(const Vector3f &rot_accel) { + // update eas2tas and air density +#if AP_AHRS_ENABLED + eas2tas = AP::ahrs().get_EAS2TAS(); +#endif + air_density = SSL_AIR_DENSITY / sq(eas2tas); + const float delta_time = frame_time_us * 1.0e-6f; + // update eas2tas and air density + eas2tas = AP_Baro::get_EAS2TAS_for_alt_amsl(location.alt*0.01); + air_density = AP_Baro::get_air_density_for_alt_amsl(location.alt*0.01); + // update rotational rates in body frame gyro += rot_accel * delta_time; @@ -628,6 +641,12 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) gyro.y = constrain_float(gyro.y, -radians(2000.0f), radians(2000.0f)); gyro.z = constrain_float(gyro.z, -radians(2000.0f), radians(2000.0f)); + // limit body accel to 64G + const float accel_limit = 64*GRAVITY_MSS; + accel_body.x = constrain_float(accel_body.x, -accel_limit, accel_limit); + accel_body.y = constrain_float(accel_body.y, -accel_limit, accel_limit); + accel_body.z = constrain_float(accel_body.z, -accel_limit, accel_limit); + // update attitude dcm.rotate(gyro * delta_time); dcm.normalize(); @@ -659,10 +678,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) velocity_air_bf = dcm.transposed() * velocity_air_ef; // airspeed - airspeed = velocity_air_ef.length(); - - // airspeed as seen by a fwd pitot tube (limited to 120m/s) - airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f); + update_eas_airspeed(); // constrain height to the ground if (on_ground()) { @@ -675,7 +691,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel) // get speed of ground movement (for ship takeoff/landing) float yaw_rate = 0; #if AP_SIM_SHIP_ENABLED - const Vector2f ship_movement = sitl->shipsim.get_ground_speed_adjustment(location, yaw_rate); + const Vector2f ship_movement = sitl->models.shipsim.get_ground_speed_adjustment(location, yaw_rate); const Vector3f gnd_movement(ship_movement.x, ship_movement.y, 0); #else const Vector3f gnd_movement; @@ -896,34 +912,13 @@ void Aircraft::smooth_sensors(void) smoothing.last_update_us = now; } -/* - return a filtered servo input as a value from -1 to 1 - servo is assumed to be 1000 to 2000, trim at 1500 - */ -float Aircraft::filtered_idx(float v, uint8_t idx) -{ - if (sitl->servo_speed <= 0) { - return v; - } - const float cutoff = 1.0f / (2 * M_PI * sitl->servo_speed); - servo_filter[idx].set_cutoff_frequency(cutoff); - - if (idx >= ARRAY_SIZE(servo_filter)) { - AP_HAL::panic("Attempt to filter invalid servo at offset %u", (unsigned)idx); - } - - return servo_filter[idx].apply(v, frame_time_us * 1.0e-6f); -} - - /* return a filtered servo input as a value from -1 to 1 servo is assumed to be 1000 to 2000, trim at 1500 */ float Aircraft::filtered_servo_angle(const struct sitl_input &input, uint8_t idx) { - const float v = (input.servos[idx] - 1500)/500.0f; - return filtered_idx(v, idx); + return servo_filter[idx].filter_angle(input.servos[idx], frame_time_us * 1.0e-6); } /* @@ -932,8 +927,14 @@ float Aircraft::filtered_servo_angle(const struct sitl_input &input, uint8_t idx */ float Aircraft::filtered_servo_range(const struct sitl_input &input, uint8_t idx) { - const float v = (input.servos[idx] - 1000)/1000.0f; - return filtered_idx(v, idx); + return servo_filter[idx].filter_range(input.servos[idx], frame_time_us * 1.0e-6); +} + +// setup filtering for servo +void Aircraft::filtered_servo_setup(uint8_t idx, uint16_t pwm_min, uint16_t pwm_max, float deflection_deg) +{ + servo_filter[idx].set_pwm_range(pwm_min, pwm_max); + servo_filter[idx].set_deflection(deflection_deg); } // extrapolate sensors by a given delta time in seconds @@ -1024,7 +1025,7 @@ void Aircraft::update_external_payload(const struct sitl_input &input) } #if AP_SIM_SHIP_ENABLED - sitl->shipsim.update(); + sitl->models.shipsim.update(); #endif // update IntelligentEnergy 2.4kW generator @@ -1167,3 +1168,37 @@ Vector3d Aircraft::get_position_relhome() const pos.xy() += home.get_distance_NE_double(origin); return pos; } + +// get air density in kg/m^3 +float Aircraft::get_air_density(float alt_amsl) const +{ + return AP_Baro::get_air_density_for_alt_amsl(alt_amsl); +} + +/* + update EAS airspeed and pitot speed + */ +void Aircraft::update_eas_airspeed() +{ + airspeed = velocity_air_ef.length() / eas2tas; + + /* + airspeed as seen by a fwd pitot tube (limited to 120m/s) + */ + airspeed_pitot = airspeed; + + // calculate angle between the local flow vector and a pitot tube aligned with the X body axis + const float pitot_aoa = atan2f(sqrtf(sq(velocity_air_bf.y) + sq(velocity_air_bf.z)), velocity_air_bf.x); + + /* + assume the pitot can correctly capture airspeed up to 20 degrees off the nose + and follows a cose law outside that range + */ + const float max_pitot_aoa = radians(20); + if (pitot_aoa > radians(90)) { + airspeed_pitot = 0; + } else if (pitot_aoa > max_pitot_aoa) { + const float gain_factor = M_PI_2 / (radians(90) - max_pitot_aoa); + airspeed_pitot *= cosf((pitot_aoa - max_pitot_aoa) * gain_factor); + } +} diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 1d79437e9065d..8a8ade5eebff5 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -37,6 +37,7 @@ #include "SIM_Battery.h" #include #include "SIM_JSON_Master.h" +#include "ServoModel.h" namespace SITL { @@ -102,6 +103,7 @@ class Aircraft { return velocity_ef; } + // return TAS airspeed in earth frame const Vector3f &get_velocity_air_ef(void) const { return velocity_air_ef; } @@ -128,6 +130,9 @@ class Aircraft { // get position relative to home Vector3d get_position_relhome() const; + // get air density in kg/m^3 + float get_air_density(float alt_amsl) const; + // distance the rangefinder is perceiving float rangefinder_range() const; @@ -176,15 +181,15 @@ class Aircraft { Vector3f gyro; // rad/s Vector3f velocity_ef; // m/s, earth frame Vector3f wind_ef; // m/s, earth frame - Vector3f velocity_air_ef; // velocity relative to airmass, earth frame + Vector3f velocity_air_ef; // velocity relative to airmass, earth frame (true airspeed) Vector3f velocity_air_bf; // velocity relative to airmass, body frame Vector3d position; // meters, NED from origin float mass; // kg float external_payload_mass; // kg Vector3f accel_body{0.0f, 0.0f, -GRAVITY_MSS}; // m/s/s NED, body frame - float airspeed; // m/s, apparent airspeed - float airspeed_pitot; // m/s, apparent airspeed, as seen by fwd pitot tube - float battery_voltage = 0.0f; + float airspeed; // m/s, EAS airspeed + float airspeed_pitot; // m/s, EAS airspeed, as seen by fwd pitot tube + float battery_voltage; float battery_current; float local_ground_level; // ground level at local position bool lock_step_scheduled; @@ -241,6 +246,8 @@ class Aircraft { bool use_time_sync = true; float last_speedup = -1.0f; const char *config_ = ""; + float eas2tas = 1.0; + float air_density = SSL_AIR_DENSITY; // allow for AHRS_ORIENTATION AP_Int8 *ahrs_orientation; @@ -257,6 +264,7 @@ class Aircraft { } ground_behavior; bool use_smoothing; + bool disable_origin_movement; float ground_height_difference() const; @@ -297,9 +305,9 @@ class Aircraft { void update_wind(const struct sitl_input &input); // return filtered servo input as -1 to 1 range - float filtered_idx(float v, uint8_t idx); float filtered_servo_angle(const struct sitl_input &input, uint8_t idx); float filtered_servo_range(const struct sitl_input &input, uint8_t idx); + void filtered_servo_setup(uint8_t idx, uint16_t pwm_min, uint16_t pwm_max, float deflection_deg); // extrapolate sensors by a given delta time in seconds void extrapolate_sensors(float delta_time); @@ -313,6 +321,9 @@ class Aircraft { // get local thermal updraft float get_local_updraft(const Vector3d ¤tPos); + // update EAS speeds + void update_eas_airspeed(); + private: uint64_t last_time_us; uint32_t frame_counter; @@ -333,7 +344,7 @@ class Aircraft { Location location; } smoothing; - LowPassFilterFloat servo_filter[5]; + ServoModel servo_filter[16]; Buzzer *buzzer; Sprayer *sprayer; diff --git a/libraries/SITL/SIM_Airspeed_DLVR.cpp b/libraries/SITL/SIM_Airspeed_DLVR.cpp index 4cae7047a4ab6..265185fae4456 100644 --- a/libraries/SITL/SIM_Airspeed_DLVR.cpp +++ b/libraries/SITL/SIM_Airspeed_DLVR.cpp @@ -65,9 +65,6 @@ void SITL::Airspeed_DLVR::update(const class Aircraft &aircraft) float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - // To Do: Add a sensor board temperature offset parameter - temperature = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + temperature = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); } diff --git a/libraries/SITL/SIM_Balloon.cpp b/libraries/SITL/SIM_Balloon.cpp index 77eca0b1ab936..218610be8b465 100644 --- a/libraries/SITL/SIM_Balloon.cpp +++ b/libraries/SITL/SIM_Balloon.cpp @@ -50,7 +50,7 @@ void Balloon::update(const struct sitl_input &input) Vector3f rot_accel = -gyro * radians(400) / terminal_rotation_rate; // air resistance - Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity); + Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity) / eas2tas; float lift_accel = 0; if (!burst && released) { diff --git a/libraries/SITL/SIM_DroneCANDevice.cpp b/libraries/SITL/SIM_DroneCANDevice.cpp index 598a53a0dadeb..de7d43c451d7e 100644 --- a/libraries/SITL/SIM_DroneCANDevice.cpp +++ b/libraries/SITL/SIM_DroneCANDevice.cpp @@ -92,11 +92,10 @@ void DroneCANDevice::update_baro() { } #if !APM_BUILD_TYPE(APM_BUILD_ArduSub) - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - float p = SSL_AIR_PRESSURE * delta; - float T = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); + float p, t_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, t_K); + float T = KELVIN_TO_C(t_K); AP_Baro_SITL::temperature_adjustment(p, T); T = C_TO_KELVIN(T); @@ -131,11 +130,8 @@ void DroneCANDevice::update_airspeed() { // this was mostly swiped from SIM_Airspeed_DLVR: const float sim_alt = AP::sitl()->state.altitude; - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - // To Do: Add a sensor board temperature offset parameter - msg.static_air_temperature = SSL_AIR_TEMPERATURE * theta + 25.0; + msg.static_air_temperature = C_TO_KELVIN(AP_Baro::get_temperatureC_for_alt_amsl(sim_alt)); static Canard::Publisher raw_air_pub{CanardInterface::get_test_iface()}; raw_air_pub.broadcast(msg); diff --git a/libraries/SITL/SIM_ELRS.cpp b/libraries/SITL/SIM_ELRS.cpp new file mode 100644 index 0000000000000..3136c762124b4 --- /dev/null +++ b/libraries/SITL/SIM_ELRS.cpp @@ -0,0 +1,165 @@ +#include + +// Only support ELRS simulation in SITL (not Sim on Hardware) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + +#include "SIM_ELRS.h" +#include + +#include +#include + +#include "include/mavlink/v2.0/all/mavlink.h" + +// Example command: -A --serial2=sim:ELRS +// TCP connection will be started on normal AP port eg 5763 for serial 2 + +// Baud rate must be set correctly +// param set SERIAL2_BAUD 460 + +using namespace SITL; + +ELRS::ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state) : + // Mirror typical ELRS UART buffer sizes + SerialDevice::SerialDevice(64, 128), + target_address("127.0.0.1"), + target_port(5761 + portNumber), + // Mirror MAVLink buffer sizes + mavlinkInputBuffer(2048), + mavlinkOutputBuffer(2048), + // Typical setup is about 500 B /s + input_data_rate(500), + output_data_rate(500), + // 255 is typically used by the GCS, for RC override to work in ArduPilot `SYSID_MYGCS` must be set to this value (255 is the default) + this_system_id(255), + // Strictly this is not a valid source component ID + this_component_id(MAV_COMPONENT::MAV_COMP_ID_ALL) +{ + + // Setup TCP server + listener.reuseaddress(); + listener.bind(target_address, target_port); + listener.listen(1); + listener.set_blocking(false); + +} + +void ELRS::update() +{ + // Connect to incoming TCP + if (sock == nullptr) { + sock = listener.accept(0); + if (sock != nullptr) { + sock->set_blocking(false); + sock->reuseaddress(); + ::printf("ELRS connected to %s:%u\n", target_address, (unsigned)target_port); + } + } + if (sock == nullptr) { + return; + } + + // Read from AP into radio + const uint32_t input_space = mavlinkInputBuffer.space(); + if (input_space > 0) { + uint8_t buf[input_space]; + ssize_t len = read_from_autopilot((char*)buf, input_space); + mavlinkInputBuffer.write(buf, len); + } + + // Send from radio to GCS + const uint32_t send_bytes = input_limit.max_bytes(input_data_rate); + if (send_bytes > 0) { + uint8_t buf[send_bytes]; + const uint32_t len = mavlinkInputBuffer.read(buf, send_bytes); + if (len > 0) { + sock->send(buf, len); + } + } + + // Incoming data from GCS to radio + const uint32_t receive_bytes = output_limit.max_bytes(output_data_rate); + if (receive_bytes > 0) { + uint8_t buf[receive_bytes]; + const ssize_t len = sock->recv(buf, receive_bytes, 1); + if (len > 0) { + mavlinkOutputBuffer.write(buf, len); + } else if (len == 0) { + // EOF, go back to waiting for a new connection + delete sock; + sock = nullptr; + } + } + + // Write from radio to AP + sendQueuedData(); +} + +// Function to behave like MAVLink libs `mavlink_parse_char` but use local buffer +uint8_t ELRS::mavlink_parse_char_helper(uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + uint8_t msg_received = mavlink_frame_char_buffer(&mavlink.rxmsg, &mavlink.status, c, r_message, r_mavlink_status); + if ((msg_received == MAVLINK_FRAMING_BAD_CRC) || (msg_received == MAVLINK_FRAMING_BAD_SIGNATURE)) { + return 0; + } + return msg_received; +} + +// Send incoming data to AP, this is a re-implementation of the ELRS function found here: +// https://github.com/ExpressLRS/ExpressLRS/blob/0d31863f34ca16a036e94a9c2a56038ae56c7f9e/src/src/rx-serial/SerialMavlink.cpp#L78 +void ELRS::sendQueuedData() +{ + + // Send radio messages at 100Hz + const uint32_t now = AP_HAL::millis(); + if ((now - lastSentFlowCtrl) > 10) { + lastSentFlowCtrl = now; + + // Space remaining as a percentage. + const uint8_t percentage_remaining = (mavlinkInputBuffer.space() * 100) / mavlinkInputBuffer.get_size(); + + // Populate radio status packet + const mavlink_radio_status_t radio_status { + rxerrors: 0, + fixed: 0, + rssi: UINT8_MAX, // Unknown + remrssi: UINT8_MAX, // Unknown + txbuf: percentage_remaining, + noise: UINT8_MAX, // Unknown + remnoise: UINT8_MAX, // Unknown + }; + + uint8_t buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES]; + mavlink_message_t msg; + mavlink_msg_radio_status_encode(this_system_id, this_component_id, &msg, &radio_status); + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + write_to_autopilot((char*)buf, len); + } + + // Read one byte at a time until were done + while (true) { + uint8_t c; + if (!mavlinkOutputBuffer.read_byte(&c)) { + break; + } + + mavlink_message_t msg; + mavlink_status_t status; + + // Try parse a mavlink message + if (mavlink_parse_char_helper(c, &msg, &status)) { + // Message decoded successfully + + // Forward message to the UART + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); + uint16_t written = write_to_autopilot((char*)buf, len); + if ((written != uint16_t(-1)) && (len != written)) { + ::fprintf(stderr, "Failed to write full msg, wanted %u achieved %u (msg id: %u)\n", len, written, msg.msgid); + } + } + } + +} + +#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/SITL/SIM_ELRS.h b/libraries/SITL/SIM_ELRS.h new file mode 100644 index 0000000000000..cd0460a1bae55 --- /dev/null +++ b/libraries/SITL/SIM_ELRS.h @@ -0,0 +1,51 @@ +#pragma once + +#include +#include "SIM_SerialDevice.h" +#include +#include + +namespace SITL { + +class ELRS : public SerialDevice { +public: + ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state); + + uint32_t device_baud() const override { return 460800; } + + void update(); + +private: + void sendQueuedData(); + + struct { + mavlink_message_t rxmsg; + mavlink_status_t status; + } mavlink; + + uint8_t mavlink_parse_char_helper(uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); + + ByteBuffer mavlinkInputBuffer; + ByteBuffer mavlinkOutputBuffer; + + DataRateLimit input_limit; + DataRateLimit output_limit; + + uint32_t lastSentFlowCtrl; + + const uint8_t this_system_id; + const uint8_t this_component_id; + + // Air data rate limits in bytes per second + const float input_data_rate; + const float output_data_rate; + + // Sockets for communicating with GCS + SocketAPM_native listener {false}; + SocketAPM_native *sock = nullptr; + const char *target_address; + const uint16_t target_port; + +}; + +} diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index 0f9bc5fb6260c..d5435047f95fb 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -323,12 +323,7 @@ static Frame supported_frames[] = // get air density in kg/m^3 float Frame::get_air_density(float alt_amsl) const { - float sigma, delta, theta; - - AP_Baro::SimpleAtmosphere(alt_amsl * 0.001f, sigma, delta, theta); - - const float air_pressure = SSL_AIR_PRESSURE * delta; - return air_pressure / (ISA_GAS_CONSTANT * (C_TO_KELVIN(model.refTempC))); + return AP_Baro::get_air_density_for_alt_amsl(alt_amsl); } /* diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 38735248d97e2..15eafb90b01c0 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -462,10 +462,9 @@ GPS_Data GPS::interpolate_data(const GPS_Data &d, uint32_t delay_ms) return _gps_history[N-1]; } -float GPS_Data::heading() const +float GPS_Data::ground_track_rad() const { - const auto velocity = Vector2d{speedE, speedN}; - return velocity.angle(); + return atan2f(speedE, speedN); } float GPS_Data::speed_2d() const diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index f92375f55844a..954bbd45acef3 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -49,8 +49,9 @@ struct GPS_Data { float speed_acc; uint8_t num_sats; - // Get heading [rad], where 0 = North in WGS-84 coordinate system - float heading() const WARN_IF_UNUSED; + // Get course over ground [rad], where 0 = North in WGS-84 coordinate system. + // Calculated from 2D velocity. + float ground_track_rad() const WARN_IF_UNUSED; // Get 2D speed [m/s] in WGS-84 coordinate system float speed_2d() const WARN_IF_UNUSED; diff --git a/libraries/SITL/SIM_GPS_NMEA.cpp b/libraries/SITL/SIM_GPS_NMEA.cpp index c4b16b89da44f..bda820cabfbdd 100644 --- a/libraries/SITL/SIM_GPS_NMEA.cpp +++ b/libraries/SITL/SIM_GPS_NMEA.cpp @@ -79,13 +79,13 @@ void GPS_NMEA::publish(const GPS_Data *d) const float speed_mps = d->speed_2d(); const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS; - const auto heading_rad = d->heading(); + const auto ground_track_deg = degrees(d->ground_track_rad()); //$GPVTG,133.18,T,120.79,M,0.11,N,0.20,K,A*24 nmea_printf("$GPVTG,%.2f,T,%.2f,M,%.2f,N,%.2f,K,A", tstring, - heading_rad, - heading_rad, + ground_track_deg, + ground_track_deg, speed_knots, speed_knots * KNOTS_TO_METERS_PER_SECOND * 3.6); @@ -95,7 +95,7 @@ void GPS_NMEA::publish(const GPS_Data *d) lat_string, lng_string, speed_knots, - heading_rad, + ground_track_deg, dstring); if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_HDT) { @@ -112,7 +112,7 @@ void GPS_NMEA::publish(const GPS_Data *d) d->altitude, wrap_360(d->yaw_deg), d->pitch_deg, - heading_rad, + ground_track_deg, speed_mps, d->roll_deg, d->have_lock?1:0, // 2=rtkfloat 3=rtkfixed, diff --git a/libraries/SITL/SIM_GPS_Trimble.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp index 1e1726b33376b..9bb3edd541eac 100644 --- a/libraries/SITL/SIM_GPS_Trimble.cpp +++ b/libraries/SITL/SIM_GPS_Trimble.cpp @@ -175,7 +175,7 @@ void GPS_Trimble::publish(const GPS_Data *d) GSOF_VEL_LEN, vel_flags, gsof_pack_float(d->speed_2d()), - gsof_pack_float(d->heading()), + gsof_pack_float(d->ground_track_rad()), // Trimble API has ambiguous direction here. // Intentionally narrow from double. gsof_pack_float(static_cast(d->speedD)) diff --git a/libraries/SITL/SIM_GPS_UBLOX.cpp b/libraries/SITL/SIM_GPS_UBLOX.cpp index 5d743cbfe9b3a..507d767df9f0c 100644 --- a/libraries/SITL/SIM_GPS_UBLOX.cpp +++ b/libraries/SITL/SIM_GPS_UBLOX.cpp @@ -216,7 +216,7 @@ void GPS_UBlox::publish(const GPS_Data *d) if (velned.heading_2d < 0.0f) { velned.heading_2d += 360.0f * 100000.0f; } - velned.speed_accuracy = 40; + velned.speed_accuracy = _sitl->gps_vel_err[instance].get().xy().length() * 100; // m/s -> cm/s velned.heading_accuracy = 4; memset(&sol, 0, sizeof(sol)); @@ -260,7 +260,7 @@ void GPS_UBlox::publish(const GPS_Data *d) pvt.velD = 1000.0f * d->speedD; pvt.gspeed = norm(d->speedN, d->speedE) * 1000; pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5; - pvt.s_acc = 40; + pvt.s_acc = velned.speed_accuracy; pvt.head_acc = 38 * 1.0e5; pvt.p_dop = 65535; memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1)); diff --git a/libraries/SITL/SIM_Glider.cpp b/libraries/SITL/SIM_Glider.cpp new file mode 100644 index 0000000000000..5ac36148d4ea6 --- /dev/null +++ b/libraries/SITL/SIM_Glider.cpp @@ -0,0 +1,412 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + glider model for high altitude balloon drop + */ + +#include "SIM_Glider.h" + +#if AP_SIM_GLIDER_ENABLED + +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +using namespace SITL; + +// SITL glider parameters +const AP_Param::GroupInfo Glider::var_info[] = { + // @Param: BLN_BRST + // @DisplayName: balloon burst height + // @Description: balloon burst height + // @Units: m + AP_GROUPINFO("BLN_BRST", 1, Glider, balloon_burst_amsl, 30000), + + // @Param: BLN_RATE + // @DisplayName: balloon climb rate + // @Description: balloon climb rate + // @Units: m/s + AP_GROUPINFO("BLN_RATE", 2, Glider, balloon_rate, 5.5), + + AP_GROUPEND +}; + +Glider::Glider(const char *frame_str) : + Aircraft(frame_str) +{ + ground_behavior = GROUND_BEHAVIOR_NO_MOVEMENT; + carriage_state = carriageState::WAITING_FOR_PICKUP; + AP::sitl()->models.glider_ptr = this; + AP_Param::setup_object_defaults(this, var_info); +} + + +// Torque calculation function +Vector3f Glider::getTorque(float inputAileron, float inputElevator, float inputRudder, const Vector3f &force) const +{ + // Calculate dynamic pressure + const auto &m = model; + double qPa = 0.5*air_density*sq(velocity_air_bf.length()); + const float aileron_rad = inputAileron * radians(m.aileronDeflectionLimitDeg); + const float elevator_rad = inputElevator * radians(m.elevatorDeflectionLimitDeg); + const float rudder_rad = inputRudder * radians(m.rudderDeflectionLimitDeg); + const float tas = MAX(airspeed * AP::ahrs().get_EAS2TAS(), 1); + + float Cl = (m.Cl2 * sq(alpharad) + m.Cl1 * alpharad + m.Cl0) * betarad; + float Cm = m.Cm2 * sq(alpharad) + m.Cm1 * alpharad + m.Cm0; + float Cn = (m.Cn2 * sq(alpharad) + m.Cn1 * alpharad + m.Cn0) * betarad; + + Cl += m.deltaClperRadianElev * elevator_rad; + Cm += m.deltaCmperRadianElev * elevator_rad; + Cn += m.deltaCnperRadianElev * elevator_rad; + + Cl += m.deltaClperRadianRud * rudder_rad; + Cm += m.deltaCmperRadianRud * rudder_rad; + Cn += m.deltaCnperRadianRud * rudder_rad; + + Cl += (m.deltaClperRadianAil2 * sq(alpharad) + m.deltaClperRadianAil1 * alpharad + m.deltaClperRadianAil0) * aileron_rad; + Cm += m.deltaCmperRadianAil * aileron_rad; + Cn += (m.deltaCnperRadianAil2 * sq(alpharad) + m.deltaCnperRadianAil1 * alpharad + m.deltaCnperRadianAil0) * aileron_rad; + + // derivatives + float Clp = m.Clp2 * sq(alpharad) + m.Clp1 * alpharad + m.Clp0; + float Clr = m.Clr2 * sq(alpharad) + m.Clr1 * alpharad + m.Clr0; + float Cnp = m.Cnp2 * sq(alpharad) + m.Cnp1 * alpharad + m.Cnp0; + float Cnr = m.Cnr2 * sq(alpharad) + m.Cnr1 * alpharad + m.Cnr0; + + // normalise gyro rates + Vector3f pqr_norm = gyro; + pqr_norm.x *= 0.5 * m.refSpan / tas; + pqr_norm.y *= 0.5 * m.refChord / tas; + pqr_norm.z *= 0.5 * m.refSpan / tas; + + Cl += pqr_norm.x * Clp; + Cl += pqr_norm.z * Clr; + Cn += pqr_norm.x * Cnp; + Cn += pqr_norm.z * Cnr; + + Cm += pqr_norm.y * m.Cmq; + + float Mx = Cl * qPa * m.Sref * m.refSpan; + float My = Cm * qPa * m.Sref * m.refChord; + float Mz = Cn * qPa * m.Sref * m.refSpan; + + +#if 0 + AP::logger().Write("GLT", "TimeUS,Alpha,Beta,Cl,Cm,Cn", "Qfffff", + AP_HAL::micros64(), + degrees(alpharad), + degrees(betarad), + Cl, Cm, Cn); +#endif + + return Vector3f(Mx/m.IXX, My/m.IYY, Mz/m.IZZ); +} + +// Force calculation, return vector in Newtons +Vector3f Glider::getForce(float inputAileron, float inputElevator, float inputRudder) +{ + const auto &m = model; + const float aileron_rad = inputAileron * radians(m.aileronDeflectionLimitDeg); + const float elevator_rad = inputElevator * radians(m.elevatorDeflectionLimitDeg); + const float rudder_rad = inputRudder * radians(m.rudderDeflectionLimitDeg); + + // dynamic pressure + double qPa = 0.5*air_density*sq(velocity_air_bf.length()); + + float CA = m.CA2 * sq(alpharad) + m.CA1 * alpharad + m.CA0; + float CY = (m.CY2 * sq(alpharad) + m.CY1 * alpharad + m.CY0) * betarad; + float CN = m.CN2 * sq(alpharad) + m.CN1 * alpharad + m.CN0; + + CN += m.deltaCNperRadianElev * elevator_rad; + CA += m.deltaCAperRadianElev * elevator_rad; + CY += m.deltaCYperRadianElev * elevator_rad; + + CN += m.deltaCNperRadianRud * rudder_rad; + CA += m.deltaCAperRadianRud * rudder_rad; + CY += m.deltaCYperRadianRud * rudder_rad; + + CN += m.deltaCNperRadianAil * aileron_rad; + CA += m.deltaCAperRadianAil * aileron_rad; + CY += m.deltaCYperRadianAil * aileron_rad; + + float Fx = -CA * qPa * m.Sref; + float Fy = CY * qPa * m.Sref; + float Fz = -CN * qPa * m.Sref; + + Vector3f ret = Vector3f(Fx, Fy, Fz); + + float Flift = Fx * sin(alpharad) - Fz * cos(alpharad); + float Fdrag = -Fx * cos(alpharad) - Fz * sin(alpharad); + + if (carriage_state == carriageState::RELEASED) { + uint32_t now = AP_HAL::millis(); + sim_LD = 0.1 * constrain_float(Flift/MAX(1.0e-6,Fdrag),0,20) + 0.9 * sim_LD; + if (now - last_drag_ms > 10 && + airspeed > 1) { + last_drag_ms = now; +#if HAL_LOGGING_ENABLED + AP::logger().Write("SLD", "TimeUS,AltFt,AltM,EAS,TAS,AD,Fl,Fd,LD,Elev,AoA,Fx,Fy,Fz,q", "Qffffffffffffff", + AP_HAL::micros64(), + (location.alt*0.01)/FEET_TO_METERS, + location.alt*0.01, + velocity_air_bf.length()/eas2tas, + velocity_air_bf.length(), + air_density, + Flift, Fdrag, sim_LD, + degrees(elevator_rad), + degrees(alpharad), + Fx, Fy, Fz, + qPa); + AP::logger().Write("SL2", "TimeUS,AltFt,KEAS,KTAS,AD,Fl,Fd,LD,Elev,Ail,Rud,AoA,SSA,q,Az", "Qffffffffffffff", + AP_HAL::micros64(), + (location.alt*0.01)/FEET_TO_METERS, + M_PER_SEC_TO_KNOTS*velocity_air_bf.length()/eas2tas, + M_PER_SEC_TO_KNOTS*velocity_air_bf.length(), + air_density, + Flift, Fdrag, sim_LD, + degrees(elevator_rad), + degrees(aileron_rad), + degrees(rudder_rad), + degrees(alpharad), + degrees(betarad), + qPa, + accel_body.z); + + AP::logger().Write("SCTL", "TimeUS,Ail,Elev,Rudd", "Qfff", + AP_HAL::micros64(), + degrees(aileron_rad), + degrees(elevator_rad), + degrees(rudder_rad)); +#endif // HAL_LOGGING_ENABLED + } + } + + + return ret; +} + +void Glider::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel) +{ + filtered_servo_setup(1, 1100, 1900, model.aileronDeflectionLimitDeg); + filtered_servo_setup(4, 1100, 1900, model.aileronDeflectionLimitDeg); + filtered_servo_setup(2, 1100, 1900, model.elevatorDeflectionLimitDeg); + filtered_servo_setup(3, 1100, 1900, model.rudderDeflectionLimitDeg); + + float aileron = 0.5*(filtered_servo_angle(input, 1) + filtered_servo_angle(input, 4)); + float elevator = filtered_servo_angle(input, 2); + float rudder = filtered_servo_angle(input, 3); + float balloon = filtered_servo_range(input, 5); + float balloon_cut = filtered_servo_range(input, 9); + + // Move balloon upwards using balloon velocity from channel 6 + // Aircraft is released from ground constraint when channel 6 PWM > 1010 + // Once released, plane will be dropped when balloon_burst_amsl is reached or channel 6 is set to PWM 1000 + if (carriage_state == carriageState::WAITING_FOR_RELEASE) { + balloon_velocity = Vector3f(-wind_ef.x, -wind_ef.y, -wind_ef.z -balloon_rate * balloon); + balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us); + const float height_AMSL = 0.01f * (float)home.alt - position.z; + // release at burst height or when channel 9 goes high + if (hal.scheduler->is_system_initialized() && + (height_AMSL > balloon_burst_amsl || balloon_cut > 0.8)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "pre-release at %i m AMSL\n", (int)height_AMSL); + carriage_state = carriageState::PRE_RELEASE; + } + } else if (carriage_state == carriageState::PRE_RELEASE) { + // slow down for release + balloon_velocity *= 0.999; + balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us); + if (balloon_velocity.length() < 0.5) { + carriage_state = carriageState::RELEASED; + use_smoothing = false; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "released at %.0f m AMSL\n", (0.01f * home.alt) - position.z); + } + } else if (carriage_state == carriageState::WAITING_FOR_PICKUP) { + // Don't allow the balloon to drag sideways until the pickup + balloon_velocity = Vector3f(0.0f, 0.0f, -balloon_rate * balloon); + balloon_position += balloon_velocity * (1.0e-6 * (float)frame_time_us); + } + + // calculate angle of attack + alpharad = atan2f(velocity_air_bf.z, velocity_air_bf.x); + betarad = atan2f(velocity_air_bf.y,velocity_air_bf.x); + + alpharad = constrain_float(alpharad, -model.alphaRadMax, model.alphaRadMax); + betarad = constrain_float(betarad, -model.betaRadMax, model.betaRadMax); + + Vector3f force; + + if (!update_balloon(balloon, force, rot_accel)) { + force = getForce(aileron, elevator, rudder); + rot_accel = getTorque(aileron, elevator, rudder, force); + } + + accel_body = force / model.mass; + + if (on_ground()) { + // add some ground friction + Vector3f vel_body = dcm.transposed() * velocity_ef; + accel_body.x -= vel_body.x * 0.3f; + } + + // constrain accelerations + accel_body.x = constrain_float(accel_body.x, -16*GRAVITY_MSS, 16*GRAVITY_MSS); + accel_body.y = constrain_float(accel_body.y, -16*GRAVITY_MSS, 16*GRAVITY_MSS); + accel_body.z = constrain_float(accel_body.z, -16*GRAVITY_MSS, 16*GRAVITY_MSS); + +} + +/* + update the plane simulation by one time step + */ +void Glider::update(const struct sitl_input &input) +{ + Vector3f rot_accel; + + update_wind(input); + + calculate_forces(input, rot_accel, accel_body); + + if (carriage_state == carriageState::WAITING_FOR_PICKUP) { + // Handle special case where plane is being held nose down waiting to be lifted + accel_body = dcm.transposed() * Vector3f(0.0f, 0.0f, -GRAVITY_MSS); + velocity_ef.zero(); + gyro.zero(); + dcm.from_euler(0.0f, radians(-80.0f), radians(home_yaw)); + use_smoothing = true; + adjust_frame_time(constrain_float(sitl->loop_rate_hz, rate_hz-1, rate_hz+1)); + } else { + update_dynamics(rot_accel); + } + update_external_payload(input); + + // update lat/lon/altitude + update_position(); + time_advance(); + + // update magnetic field + update_mag_field_bf(); +} + +/* + return true if we are on the ground +*/ +bool Glider::on_ground() const +{ + switch (carriage_state) { + case carriageState::NONE: + case carriageState::RELEASED: + return hagl() <= 0.001; + case carriageState::WAITING_FOR_PICKUP: + case carriageState::WAITING_FOR_RELEASE: + case carriageState::PRE_RELEASE: + // prevent bouncing around ground + // don't do ground interaction if being carried + break; + } + return false; +} + +/* + implement balloon lift + controlled by SIM_BLN_BRST and SIM_BLN_RATE + */ +bool Glider::update_balloon(float balloon, Vector3f &force, Vector3f &rot_accel) +{ + if (!hal.util->get_soft_armed()) { + return false; + } + + switch (carriage_state) { + case carriageState::NONE: + case carriageState::RELEASED: + // balloon not active + disable_origin_movement = false; + return false; + + case carriageState::WAITING_FOR_PICKUP: + case carriageState::WAITING_FOR_RELEASE: + case carriageState::PRE_RELEASE: + // while under balloon disable origin movement to allow for balloon position calculations + disable_origin_movement = true; + break; + } + + // assume a 50m tether with a 1Hz pogo frequency and damping ratio of 0.2 + Vector3f tether_pos_bf{-1.0f,0.0f,0.0f}; // tether attaches to vehicle tail approx 1m behind c.g. + const float omega = model.tetherPogoFreq * M_2PI; // rad/sec + const float zeta = 0.7f; + float tether_stiffness = model.mass * sq(omega); // N/m + float tether_damping = 2.0f * zeta * omega / model.mass; // N/(m/s) + // NED relative position vector from tether attachment on plane to balloon attachment + Vector3f relative_position = balloon_position - (position.tofloat() + (dcm * tether_pos_bf)); + const float separation_distance = relative_position.length(); + + // NED unit vector pointing from tether attachment on plane to attachment on balloon + Vector3f tether_unit_vec_ef = relative_position.normalized(); + + // NED velocity of attahment point on plane + Vector3f attachment_velocity_ef = velocity_ef + dcm * (gyro % tether_pos_bf); + + // NED velocity of attachment point on balloon as seen by observer on attachemnt point on plane + Vector3f relative_velocity = balloon_velocity - attachment_velocity_ef; + + float separation_speed = relative_velocity * tether_unit_vec_ef; + + // rate increase in separation between attachment point on plane and balloon + // tension force in tether due to stiffness and damping + float tension_force = MAX(0.0f, (separation_distance - model.tetherLength) * tether_stiffness); + if (tension_force > 0.0f) { + tension_force += constrain_float(separation_speed * tether_damping, 0.0f, 0.05f * tension_force); + } + + if (carriage_state == carriageState::WAITING_FOR_PICKUP && tension_force > 1.2f * model.mass * GRAVITY_MSS && balloon > 0.01f) { + carriage_state = carriageState::WAITING_FOR_RELEASE; + } + + if (carriage_state == carriageState::WAITING_FOR_RELEASE || + carriage_state == carriageState::PRE_RELEASE) { + Vector3f tension_force_vector_ef = tether_unit_vec_ef * tension_force; + Vector3f tension_force_vector_bf = dcm.transposed() * tension_force_vector_ef; + force = tension_force_vector_bf; + + // drag force due to lateral motion assuming projected area from Y is 20% of projected area seen from Z and + // assuming bluff body drag characteristic. In reality we would need an aero model that worked flying backwards, + // but this will have to do for now. + Vector3f aero_force_bf = Vector3f(0.0f, 0.2f * velocity_air_bf.y * fabsf(velocity_air_bf.y), velocity_air_bf.z * fabsf(velocity_air_bf.z)); + aero_force_bf *= air_density * model.Sref; + force -= aero_force_bf; + + Vector3f tension_moment_vector_bf = tether_pos_bf % tension_force_vector_bf; + Vector3f tension_rot_accel = Vector3f(tension_moment_vector_bf.x/model.IXX, tension_moment_vector_bf.y/model.IYY, tension_moment_vector_bf.z/model.IZZ); + rot_accel = tension_rot_accel; + + // add some rotation damping due to air resistance assuming a 2 sec damping time constant at SL density + // TODO model roll damping with more accuracy using Clp data for zero alpha as a first approximation + rot_accel -= gyro * 0.5 * air_density; + } else { + // tether is either slack awaiting pickup or released + rot_accel.zero(); + force = dcm.transposed() * Vector3f(0.0f, 0.0f, -GRAVITY_MSS * model.mass); + } + + // balloon is active + return true; +} + +#endif // AP_SIM_GLIDER_ENABLED diff --git a/libraries/SITL/SIM_Glider.h b/libraries/SITL/SIM_Glider.h new file mode 100644 index 0000000000000..0c0aa3fa5e430 --- /dev/null +++ b/libraries/SITL/SIM_Glider.h @@ -0,0 +1,203 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + Glider model for high altitude balloon drop +*/ + +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GLIDER_ENABLED + +#include "SIM_Aircraft.h" +#include + +namespace SITL { + +/* + a very simple plane simulator + */ +class Glider : public Aircraft { +public: + Glider(const char *frame_str); + + /* update model by one time step */ + virtual void update(const struct sitl_input &input) override; + + /* static object creator */ + static Aircraft *create(const char *frame_str) { + return new Glider(frame_str); + } + + bool on_ground() const override; + + static const struct AP_Param::GroupInfo var_info[]; + +protected: + float alpharad; + float betarad; + + AP_Float balloon_burst_amsl; + AP_Float balloon_rate; + + /* + parameters that define the glider model + */ + const struct Model { + // total vehicle mass + float mass = 9.07441; // kg + + // reference area + float Sref = 0.92762; // m^2 + + float refSpan = 1.827411; // m + float refChord = 0.507614; // m + float IXX = 0.234; // kg-m^2 + float IYY = 1.85; // kg-m^2 + float IZZ = 2.04; // kg-m^2 + + // CN is coefficients for forces on +Z axis + // quadratic in alpharad + float CN2 = -0.5771; + float CN1 = 3.9496; + float CN0 = 0; + + // CA is the coefficients for forces on +X axis + // quadratic in alpharad + float CA2 = -1.6809; + float CA1 = -0.0057; + float CA0 = 0.0150; + + // CY is the coefficients for forces on the +Y axis + // quadratic in alpharad, with betarad factor + float CY2 = -3.342; + float CY1 = 0.0227; + float CY0 = -0.4608; + + // Cl is the coefficients for moments on X axis + // quadratic in alpharad, with betarad factor + float Cl2 = 0.2888; + float Cl1 = -0.8518; + float Cl0 = -0.0491; + + // Cm is the coefficients for moments on Y axis + // quadratic in alpharad + float Cm2 = 0.099; + float Cm1 = -0.6506; + float Cm0 = -0.0005; + + // Cn is the coefficients for moments on Z axis + // quadratic in alpharad, with betarad factor + float Cn2 = 0.0057; + float Cn1 = -0.0101; + float Cn0 = 0.1744; + + // controls neutral dynamic derivatives + // p, q, r are gyro rates + float Cmq = -6.1866; + + float Clp2 = 0.156; + float Clp1 = 0.0129; + float Clp0 = -0.315; + + float Clr2 = -0.0284; + float Clr1 = 0.2641; + float Clr0 = 0.0343; + + float Cnp2 = 0.0199; + float Cnp1 = -0.315; + float Cnp0 = -0.013; + + float Cnr2 = 0.1297; + float Cnr1 = 0.0343; + float Cnr0 = -0.264; + + // elevator + float elevatorDeflectionLimitDeg = -12.5; + float deltaCNperRadianElev = -0.7; + float deltaCAperRadianElev = 0.12; + float deltaCmperRadianElev = 1.39; + float deltaCYperRadianElev = 0; + float deltaClperRadianElev = 0; + float deltaCnperRadianElev = 0; + + // rudder + float rudderDeflectionLimitDeg = 18.0; + float deltaCNperRadianRud = 0; + float deltaCAperRadianRud = 0.058; + float deltaCmperRadianRud = 0; + float deltaCYperRadianRud = 0.31; + float deltaClperRadianRud = 0.038; + float deltaCnperRadianRud = -0.174; + + // aileron + float aileronDeflectionLimitDeg = 15.5; + float deltaCNperRadianAil = 0; + float deltaCAperRadianAil = 0.016; + float deltaCmperRadianAil = 0; + float deltaCYperRadianAil = -0.015; + + // quadratic in alpharad + float deltaClperRadianAil0 = 0.09191; + float deltaClperRadianAil1 = 0.0001; + float deltaClperRadianAil2 = -0.08645; + + // quadratic in alpharad + float deltaCnperRadianAil0 = 0.00789; + float deltaCnperRadianAil1 = 0.00773; + float deltaCnperRadianAil2 = -0.01162; + + // Forces in the +X direction are –CA * q * Sref + // Forces in the +Y direction are +CY * q * Sref + // Forces in the +Z direction are –CN * q *Sref + // Moments about the X axis are +Cl * q * Sref * RefSpan + // Moments about the Y axis are +Cm * q * Sref * RefChord + // Moments about the Z axis are +Cn * q * Sref * RefSpan + + // low altitude + float alphaRadMax = 0.209; + float betaRadMax = 0.209; + + // balloon launch parameters + float tetherLength = 50.0f; // length of tether from balloon to aircraft (m) + float tetherPogoFreq = 2.0f; // measured vertical frequency of on tether (Hz) + + } model; + + Vector3f getForce(float inputAileron, float inputElevator, float inputRudder); + Vector3f getTorque(float inputAileron, float inputElevator, float inputRudder, const Vector3f &force) const; + bool update_balloon(float balloon, Vector3f &force, Vector3f &rot_accel); + void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); + + Vector3f balloon_velocity; // balloon velocity NED + Vector3f balloon_position{0.0f, 0.0f, -45.0f}; // balloon position NED from origin + + enum class carriageState { + NONE = 0, // no carriage option available + WAITING_FOR_PICKUP = 1, // in launch cradle waiting to be picked up by launch vehicle + WAITING_FOR_RELEASE = 2, // being carried by luanch vehicle waitng to be released + PRE_RELEASE = 3, // had been released by launch vehicle + RELEASED = 4 // had been released by launch vehicle + } carriage_state; + bool plane_air_release; // true when plane has separated from the airborne launching platform + + uint32_t last_drag_ms; + float sim_LD; +}; + +} // namespace SITL + +#endif // AP_SIM_GLIDER_ENABLED diff --git a/libraries/SITL/SIM_InertialLabs.cpp b/libraries/SITL/SIM_InertialLabs.cpp index edaadf0b8756d..aa191f0e9ef93 100644 --- a/libraries/SITL/SIM_InertialLabs.cpp +++ b/libraries/SITL/SIM_InertialLabs.cpp @@ -39,11 +39,12 @@ void InertialLabs::send_packet(void) pkt.gyro_data_hr.x = fdm.pitchRate*1.0e5; pkt.gyro_data_hr.z = -fdm.yawRate*1.0e5; - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere((fdm.altitude+rand_float()*0.25) * 0.001, sigma, delta, theta); - pkt.baro_data.pressure_pa2 = SSL_AIR_PRESSURE * delta * 0.5; + float p, t_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(fdm.altitude+rand_float()*0.25, p, t_K); + + pkt.baro_data.pressure_pa2 = p; pkt.baro_data.baro_alt = fdm.altitude; - pkt.temperature = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); + pkt.temperature = KELVIN_TO_C(t_K); pkt.mag_data.x = (fdm.bodyMagField.y / NTESLA_TO_MGAUSS)*0.1; pkt.mag_data.y = (fdm.bodyMagField.x / NTESLA_TO_MGAUSS)*0.1; diff --git a/libraries/SITL/SIM_JSON.cpp b/libraries/SITL/SIM_JSON.cpp index 5c32227d5d459..95b51904c43dc 100644 --- a/libraries/SITL/SIM_JSON.cpp +++ b/libraries/SITL/SIM_JSON.cpp @@ -331,6 +331,9 @@ void JSON::recv_fdm(const struct sitl_input &input) // airspeed as seen by a fwd pitot tube (limited to 120m/s) airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f); + + // airspeed fix for eas2tas + update_eas_airspeed(); } // Convert from a meters from origin physics to a lat long alt diff --git a/libraries/SITL/SIM_MS5525.cpp b/libraries/SITL/SIM_MS5525.cpp index 24e2000d52c7c..760c4202f92a9 100644 --- a/libraries/SITL/SIM_MS5525.cpp +++ b/libraries/SITL/SIM_MS5525.cpp @@ -68,11 +68,7 @@ void MS5525::get_pressure_temperature_readings(float &P_Pa, float &Temp_C) float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - - // To Do: Add a sensor board temperature offset parameter - Temp_C = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + Temp_C = AP_Baro::get_temperatureC_for_alt_amsl(sim_alt); const uint8_t instance = 0; // TODO: work out which sensor this is P_Pa = AP::sitl()->state.airspeed_raw_pressure[instance] + AP::sitl()->airspeed[instance].offset; } diff --git a/libraries/SITL/SIM_MS5611.cpp b/libraries/SITL/SIM_MS5611.cpp index a1957df17da61..d205665d5ef88 100644 --- a/libraries/SITL/SIM_MS5611.cpp +++ b/libraries/SITL/SIM_MS5611.cpp @@ -106,15 +106,14 @@ void MS5611::check_conversion_accuracy(float P_Pa, float Temp_C, uint32_t D1, ui void MS5611::get_pressure_temperature_readings(float &P_Pa, float &Temp_C) { - float sigma, delta, theta; - float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - P_Pa = SSL_AIR_PRESSURE * delta; + float p, T_K; + AP_Baro::get_pressure_temperature_for_alt_amsl(sim_alt, p, T_K); - Temp_C = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta) + AP::sitl()->temp_board_offset; + P_Pa = p; + Temp_C = KELVIN_TO_C(T_K) + AP::sitl()->temp_board_offset; // TO DO add in temperature adjustment by inheritting from AP_Baro_SITL_Generic? // AP_Baro_SITL::temperature_adjustment(P_Pa, Temp_C); diff --git a/libraries/SITL/SIM_MS5XXX.cpp b/libraries/SITL/SIM_MS5XXX.cpp index 053a832048390..faca67f0bd7af 100644 --- a/libraries/SITL/SIM_MS5XXX.cpp +++ b/libraries/SITL/SIM_MS5XXX.cpp @@ -58,6 +58,8 @@ void MS5XXX::convert_D2() // bug in the conversion code. The simulation can pass in // very, very low numbers. Clamp it. P_Pa = 0.1; + + // This should be a simulation error??? Pressure at 86km is 0.374Pa } uint32_t D1; diff --git a/libraries/SITL/SIM_MicroStrain.cpp b/libraries/SITL/SIM_MicroStrain.cpp index af4b2c26d6cfe..d56cc87fce4c1 100644 --- a/libraries/SITL/SIM_MicroStrain.cpp +++ b/libraries/SITL/SIM_MicroStrain.cpp @@ -101,9 +101,9 @@ void MicroStrain::send_imu_packet(void) // Add ambient pressure field packet.payload[packet.payload_size++] = 0x06; // Ambient Pressure Field Size packet.payload[packet.payload_size++] = 0x17; // Descriptor - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(fdm.altitude * 0.001f, sigma, delta, theta); - put_float(packet, SSL_AIR_PRESSURE * delta * 0.001 + rand_float() * 0.1); + + float pressure_Pa = AP_Baro::get_pressure_for_alt_amsl(fdm.altitude); + put_float(packet, pressure_Pa*0.001 + rand_float() * 0.1); // Add scaled magnetometer field packet.payload[packet.payload_size++] = 0x0E; // Scaled Magnetometer Field Size diff --git a/libraries/SITL/SIM_Plane.h b/libraries/SITL/SIM_Plane.h index 53bb998e461cd..9b663889b0cb1 100644 --- a/libraries/SITL/SIM_Plane.h +++ b/libraries/SITL/SIM_Plane.h @@ -41,7 +41,6 @@ class Plane : public Aircraft { protected: const float hover_throttle = 0.7f; - const float air_density = 1.225; // kg/m^3 at sea level, ISA conditions float angle_of_attack; float beta; diff --git a/libraries/SITL/SIM_Precland.cpp b/libraries/SITL/SIM_Precland.cpp index 50af3960cdf5b..818d652bad8db 100644 --- a/libraries/SITL/SIM_Precland.cpp +++ b/libraries/SITL/SIM_Precland.cpp @@ -150,7 +150,7 @@ void SIM_Precland::update(const Location &loc) */ auto *sitl = AP::sitl(); Location shiploc; - if (sitl != nullptr && sitl->shipsim.get_location(shiploc) && !shiploc.is_zero()) { + if (sitl != nullptr && sitl->models.shipsim.get_location(shiploc) && !shiploc.is_zero()) { shiploc.change_alt_frame(Location::AltFrame::ABOVE_ORIGIN); device_center = shiploc; } diff --git a/libraries/SITL/SIM_Scrimmage.cpp b/libraries/SITL/SIM_Scrimmage.cpp index e4d91548ac34f..9af2b7999194c 100644 --- a/libraries/SITL/SIM_Scrimmage.cpp +++ b/libraries/SITL/SIM_Scrimmage.cpp @@ -106,7 +106,7 @@ void Scrimmage::recv_fdm(const struct sitl_input &input) // velocity relative to air mass, in earth frame TODO - velocity_air_ef = velocity_ef; + velocity_air_ef = velocity_ef - wind_ef; // velocity relative to airmass in body frame TODO velocity_air_bf = dcm.transposed() * velocity_air_ef; diff --git a/libraries/SITL/SIM_SingleCopter.cpp b/libraries/SITL/SIM_SingleCopter.cpp index d12699c4b8ffc..dc6bd719f4c29 100644 --- a/libraries/SITL/SIM_SingleCopter.cpp +++ b/libraries/SITL/SIM_SingleCopter.cpp @@ -90,7 +90,7 @@ void SingleCopter::update(const struct sitl_input &input) rot_accel.z -= gyro.z * radians(400.0) / terminal_rotation_rate; // air resistance - Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity); + Vector3f air_resistance = -velocity_air_ef * (GRAVITY_MSS/terminal_velocity) / eas2tas; // scale thrust to newtons thrust *= thrust_scale; diff --git a/libraries/SITL/SIM_StratoBlimp.cpp b/libraries/SITL/SIM_StratoBlimp.cpp new file mode 100644 index 0000000000000..915fceb7a1dce --- /dev/null +++ b/libraries/SITL/SIM_StratoBlimp.cpp @@ -0,0 +1,311 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + StratoBlimp simulator class +*/ + +#include "SIM_StratoBlimp.h" + +#if AP_SIM_STRATOBLIMP_ENABLED + +#include +#include + +#include + +using namespace SITL; + +extern const AP_HAL::HAL& hal; + +// SITL StratoBlimp parameters +const AP_Param::GroupInfo StratoBlimp::var_info[] = { + // @Param: MASS + // @DisplayName: mass + // @Description: mass of blimp not including lifting gas + // @Units: kg + AP_GROUPINFO("MASS", 1, StratoBlimp, mass, 80), + + // @Param: HMASS + // @DisplayName: helium mass + // @Description: mass of lifting gas + // @Units: kg + AP_GROUPINFO("HMASS", 2, StratoBlimp, helium_mass, 13.54), + + // @Param: ARM_LEN + // @DisplayName: arm length + // @Description: distance from center of mass to one motor + // @Units: m + AP_GROUPINFO("ARM_LEN", 3, StratoBlimp, arm_length, 3.6), + + // @Param: MOT_THST + // @DisplayName: motor thrust + // @Description: thrust at max throttle for one motor + // @Units: N + AP_GROUPINFO("MOT_THST", 4, StratoBlimp, motor_thrust, 145), + + // @Param: DRAG_FWD + // @DisplayName: drag in forward direction + // @Description: drag on X axis + AP_GROUPINFO("DRAG_FWD", 5, StratoBlimp, drag_fwd, 0.27), + + // @Param: DRAG_SIDE + // @DisplayName: drag in sidewards direction + // @Description: drag on Y axis + AP_GROUPINFO("DRAG_SIDE", 16, StratoBlimp, drag_side, 0.5), + + // @Param: DRAG_UP + // @DisplayName: drag in upward direction + // @Description: drag on Z axis + AP_GROUPINFO("DRAG_UP", 6, StratoBlimp, drag_up, 0.4), + + // @Param: MOI_YAW + // @DisplayName: moment of inertia in yaw + // @Description: moment of inertia in yaw + AP_GROUPINFO("MOI_YAW", 7, StratoBlimp, moi_yaw, 2800), + + // @Param: MOI_ROLL + // @DisplayName: moment of inertia in roll + // @Description: moment of inertia in roll + AP_GROUPINFO("MOI_ROLL", 8, StratoBlimp, moi_roll, 1400), + + // @Param: MOI_PITCH + // @DisplayName: moment of inertia in pitch + // @Description: moment of inertia in pitch + AP_GROUPINFO("MOI_PITCH", 9, StratoBlimp, moi_pitch, 3050), + + // @Param: ALT_TARG + // @DisplayName: altitude target + // @Description: altitude target + // @Units: m + AP_GROUPINFO("ALT_TARG", 10, StratoBlimp, altitude_target, 20000), + + // @Param: CLMB_RT + // @DisplayName: target climb rate + // @Description: target climb rate + // @Units: m/s + AP_GROUPINFO("CLMB_RT", 11, StratoBlimp, target_climb_rate, 5), + + // @Param: YAW_RT + // @DisplayName: yaw rate + // @Description: maximum yaw rate with full left throttle at target altitude + // @Units: deg/s + AP_GROUPINFO("YAW_RT", 12, StratoBlimp, yaw_rate_max, 60), + + // @Param: MOT_ANG + // @DisplayName: motor angle + // @Description: maximum motor tilt angle + // @Units: deg + AP_GROUPINFO("MOT_ANG", 13, StratoBlimp, motor_angle, 20), + + // @Param: COL + // @DisplayName: center of lift + // @Description: center of lift position above CoG + // @Units: m + AP_GROUPINFO("COL", 14, StratoBlimp, center_of_lift, 2.54), + + // @Param: WVANE + // @DisplayName: weathervaning offset + // @Description: center of drag for weathervaning + // @Units: m + AP_GROUPINFO("WVANE", 15, StratoBlimp, center_of_drag, 0.3), + + // @Param: FLR + // @DisplayName: free lift rate + // @Description: amount of additional lift generated by the helper balloon (for the purpose of ascent), as a proportion of the 'neutral buoyancy' lift + AP_GROUPINFO("FLR", 17, StratoBlimp, free_lift_rate, 0.12), + + AP_GROUPEND +}; + +StratoBlimp::StratoBlimp(const char *frame_str) : + Aircraft(frame_str) +{ + AP::sitl()->models.stratoblimp_ptr = this; + AP_Param::setup_object_defaults(this, var_info); +} + +/* + calculate coefficients to match parameters + */ +void StratoBlimp::calculate_coefficients(void) +{ + // calculate yaw drag based on turn rate at the given altitude + drag_yaw = 1.0; + + // get full throttle rotational accel for one motor + Vector3f body_acc, rot_accel; + handle_motor(1, 0, body_acc, rot_accel, -arm_length); + + // get rotational drag at target alt + Vector3f vel_bf, g, drag_linear, drag_rotaccel; + g.z = radians(yaw_rate_max); + + get_drag(vel_bf, g, + altitude_target, + drag_linear, drag_rotaccel); + + drag_yaw = rot_accel.z / -drag_rotaccel.z; +} + +void StratoBlimp::handle_motor(float throttle, float tilt, Vector3f &body_acc, Vector3f &rot_accel, float lateral_position) +{ + const float angle_rad = radians(motor_angle) * tilt; + const float thrust_x = motor_thrust * throttle; + const float total_mass = mass + helium_mass; + + const Vector3f thrust{cosf(angle_rad)*thrust_x, 0, -sinf(angle_rad)*thrust_x}; // assume constant with pressure alt and linear + Vector3f accel = thrust / total_mass; + Vector3f pos{0, lateral_position, 0}; + + Vector3f torque = (pos % thrust); + + rot_accel.z += torque.z / moi_yaw; + body_acc += accel; +} + + +/* + get body frame linear and rotational drag for a given velocity and altitude + */ +void StratoBlimp::get_drag(const Vector3f &velocity_linear, + const Vector3f &velocity_rot, + float altitude, + Vector3f &drag_linear, Vector3f &drag_rotaccel) +{ + Vector3f vel_air_bf = velocity_linear; + const float drag_x_sign = vel_air_bf.x>0? -1 : 1; + const float drag_y_sign = vel_air_bf.y>0? -1 : 1; + const float drag_z_sign = vel_air_bf.z>0? -1 : 1; + drag_linear.x = 0.5 * drag_x_sign * air_density * sq(vel_air_bf.x) * drag_fwd; + drag_linear.y = 0.5 * drag_y_sign * air_density * sq(vel_air_bf.y) * drag_fwd; + drag_linear.z = 0.5 * drag_z_sign * air_density * sq(vel_air_bf.z) * drag_up; + + drag_rotaccel = -velocity_rot * drag_yaw; + + /* + apply torque from drag + */ + Vector3f drag_force = drag_linear * mass; + Vector3f drag_pos{-center_of_drag, 0, -center_of_lift}; + Vector3f drag_torque = (drag_pos % drag_force); + drag_rotaccel += drag_torque / moi_pitch; +} + +/* + get vertical thrust from lift in Newtons + */ +float StratoBlimp::get_lift(float altitude) +{ + // start with neutral buoyancy + float lift_accel = GRAVITY_MSS; + + // add lift from helper balloon if still attached + if (helper_balloon_attached) { + // helper balloon additional lift amount based on Free Lift Ratio + lift_accel += GRAVITY_MSS*free_lift_rate; + // detach helper balloon if the target altitude has been reached + if (altitude >= altitude_target) { + helper_balloon_attached = false; + } + } + return mass * lift_accel; +} + +// calculate rotational and linear accelerations in body frame +void StratoBlimp::calculate_forces(const struct sitl_input &input, Vector3f &body_acc, Vector3f &rot_accel) +{ + //float delta_time = frame_time_us * 1.0e-6f; + + if (!hal.scheduler->is_system_initialized()) { + return; + } + + const float left_tilt = filtered_servo_angle(input, 0); + const float right_tilt = filtered_servo_angle(input, 1); + + const float left_throttle = filtered_servo_range(input, 2); + const float right_throttle = filtered_servo_range(input, 3); + const float ground_release = filtered_servo_range(input, 4); + + body_acc.zero(); + rot_accel.zero(); + + handle_motor(left_throttle, left_tilt, body_acc, rot_accel, -arm_length); + handle_motor(right_throttle, right_tilt, body_acc, rot_accel, arm_length); + + Vector3f drag_linear, drag_rotaccel; + get_drag(velocity_air_bf, gyro, + location.alt*0.01, + drag_linear, drag_rotaccel); + + body_acc += drag_linear; + rot_accel += drag_rotaccel; + + if (ground_release > 0.9) { + released = true; + } + if (released) { + Vector3f lift_thrust_ef{0, 0, -get_lift(location.alt*0.01)}; + Vector3f lift_thrust_bf = dcm.transposed() * lift_thrust_ef; + + body_acc += lift_thrust_bf / mass; + + /* + apply righting moment + */ + Vector3f lift_pos{0, 0, -center_of_lift}; + Vector3f lift_torque = (lift_pos % lift_thrust_bf); + rot_accel += lift_torque / moi_roll; + } +} + +/* + update the airship simulation by one time step + */ +void StratoBlimp::update(const struct sitl_input &input) +{ + air_density = get_air_density(location.alt*0.01); + EAS2TAS = sqrtf(SSL_AIR_DENSITY / air_density); + + calculate_coefficients(); + + float delta_time = frame_time_us * 1.0e-6f; + + Vector3f rot_accel = Vector3f(0,0,0); + calculate_forces(input, accel_body, rot_accel); + + // update rotational rates in body frame + gyro += rot_accel * delta_time; + + gyro.x = constrain_float(gyro.x, -radians(2000.0f), radians(2000.0f)); + gyro.y = constrain_float(gyro.y, -radians(2000.0f), radians(2000.0f)); + gyro.z = constrain_float(gyro.z, -radians(2000.0f), radians(2000.0f)); + + dcm.rotate(gyro * delta_time); + dcm.normalize(); + + update_dynamics(rot_accel); + update_external_payload(input); + + // update lat/lon/altitude + update_position(); + update_wind(input); + time_advance(); + + // update magnetic field + update_mag_field_bf(); +} + +#endif // AP_SIM_STRATOBLIMP_ENABLED diff --git a/libraries/SITL/SIM_StratoBlimp.h b/libraries/SITL/SIM_StratoBlimp.h new file mode 100644 index 0000000000000..9165770aa6f96 --- /dev/null +++ b/libraries/SITL/SIM_StratoBlimp.h @@ -0,0 +1,88 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + a stratospheric blimp simulator class +*/ + +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_STRATOBLIMP_ENABLED + +#include "SIM_Aircraft.h" +#include + +namespace SITL { + +/* + a stratospheric blimp simulator + */ + +class StratoBlimp : public Aircraft { +public: + StratoBlimp(const char *frame_str); + + /* update model by one time step */ + void update(const struct sitl_input &input) override; + + /* static object creator */ + static Aircraft *create(const char *frame_str) { + return new StratoBlimp(frame_str); + } + + static const struct AP_Param::GroupInfo var_info[]; + +protected: + void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); + +private: + void calculate_coefficients(); + void handle_motor(float throttle, float tilt, Vector3f &body_acc, Vector3f &rot_accel, float lateral_position); + void get_drag(const Vector3f &velocity_linear, + const Vector3f &velocity_rot, + float altitude, + Vector3f &drag_linear, Vector3f &drag_rotaccel); + float get_lift(float altitude); + + float air_density; + float EAS2TAS; + float drag_yaw; + bool released; + bool helper_balloon_attached = true; + + AP_Float mass; + AP_Float helium_mass; + AP_Float arm_length; + AP_Float motor_thrust; + AP_Float drag_fwd; + AP_Float drag_side; + AP_Float drag_up; + AP_Float altitude_target; + AP_Float target_climb_rate; + AP_Float turn_rate; + AP_Float motor_angle; + AP_Float yaw_rate_max; + AP_Float moi_roll; + AP_Float moi_yaw; + AP_Float moi_pitch; + AP_Float center_of_lift; + AP_Float center_of_drag; + AP_Float free_lift_rate; +}; + +} + +#endif // AP_SIM_STRATOBLIMP_ENABLED diff --git a/libraries/SITL/SIM_Temperature_TSYS01.cpp b/libraries/SITL/SIM_Temperature_TSYS01.cpp index 0c1ab789ab466..5785a731527ae 100644 --- a/libraries/SITL/SIM_Temperature_TSYS01.cpp +++ b/libraries/SITL/SIM_Temperature_TSYS01.cpp @@ -193,9 +193,6 @@ float SITL::TSYS01::get_sim_temperature() const float sim_alt = AP::sitl()->state.altitude; sim_alt += 2 * rand_float(); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); - // To Do: Add a sensor board temperature offset parameter - return (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; + return AP_Baro::get_temperatureC_for_alt_amsl(sim_alt) + 25; } diff --git a/libraries/SITL/SIM_VectorNav.cpp b/libraries/SITL/SIM_VectorNav.cpp index ee685ee88a124..27c19be7f0f4f 100644 --- a/libraries/SITL/SIM_VectorNav.cpp +++ b/libraries/SITL/SIM_VectorNav.cpp @@ -94,9 +94,8 @@ void VectorNav::send_packet1(void) pkt.uncompAngRate[1] = radians(fdm.pitchRate + gyro_noise * rand_float()); pkt.uncompAngRate[2] = radians(fdm.yawRate + gyro_noise * rand_float()); - float sigma, delta, theta; - AP_Baro::SimpleAtmosphere(fdm.altitude * 0.001f, sigma, delta, theta); - pkt.pressure = SSL_AIR_PRESSURE * delta * 0.001 + rand_float() * 0.01; + const float pressure_Pa = AP_Baro::get_pressure_for_alt_amsl(fdm.altitude); + pkt.pressure = pressure_Pa*0.001 + rand_float() * 0.01; pkt.mag[0] = fdm.bodyMagField.x*0.001; pkt.mag[1] = fdm.bodyMagField.y*0.001; @@ -153,7 +152,8 @@ void VectorNav::send_packet2(void) simulation_timeval(&tv); pkt.timeGPS = tv.tv_usec * 1000ULL; - pkt.temp = 23.5; + + pkt.temp = AP_Baro::get_temperatureC_for_alt_amsl(fdm.altitude); pkt.numGPS1Sats = 19; pkt.GPS1Fix = 3; pkt.GPS1posLLA[0] = fdm.latitude; diff --git a/libraries/SITL/SIM_config.h b/libraries/SITL/SIM_config.h index 419cac92262ba..d5f6a00192e6c 100644 --- a/libraries/SITL/SIM_config.h +++ b/libraries/SITL/SIM_config.h @@ -93,3 +93,11 @@ #ifndef AP_SIM_COMPASS_QMC5883L_ENABLED #define AP_SIM_COMPASS_QMC5883L_ENABLED AP_SIM_COMPASS_BACKEND_DEFAULT_ENABLED #endif + +#ifndef AP_SIM_STRATOBLIMP_ENABLED +#define AP_SIM_STRATOBLIMP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#ifndef AP_SIM_GLIDER_ENABLED +#define AP_SIM_GLIDER_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index abd099baf1809..7ca40de3d9d5c 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -37,6 +37,9 @@ #endif #endif // SFML_JOYSTICK +#include "SIM_StratoBlimp.h" +#include "SIM_Glider.h" + extern const AP_HAL::HAL& hal; #ifndef SIM_RATE_HZ_DEFAULT @@ -84,7 +87,11 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Units: m/s // @User: Advanced AP_GROUPINFO("WIND_TURB", 11, SIM, wind_turbulance, 0), - AP_GROUPINFO("SERVO_SPEED", 16, SIM, servo_speed, 0.14), + + // @Group: SERVO_ + // @Path: ./ServoModel.cpp + AP_SUBGROUPINFO(servo, "SERVO_", 16, SIM, ServoParams), + AP_GROUPINFO("SONAR_ROT", 17, SIM, sonar_rot, Rotation::ROTATION_PITCH_270), // @Param: BATT_VOLTAGE // @DisplayName: Simulated battery voltage @@ -175,9 +182,7 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Vector3Parameter: 1 AP_GROUPINFO("FLOW_POS", 56, SIM, optflow_pos_offset, 0), AP_GROUPINFO("ENGINE_FAIL", 58, SIM, engine_fail, 0), -#if AP_SIM_SHIP_ENABLED - AP_SUBGROUPINFO(shipsim, "SHIP_", 59, SIM, ShipSim), -#endif + AP_SUBGROUPINFO(models, "", 59, SIM, SIM::ModelParm), AP_SUBGROUPEXTENSION("", 60, SIM, var_mag), #if HAL_SIM_GPS_ENABLED AP_SUBGROUPEXTENSION("", 61, SIM, var_gps), @@ -537,7 +542,7 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // @Range: 10 100 AP_GROUPINFO("OSD_ROWS", 54, SIM, osd_rows, 16), #endif - + #ifdef SFML_JOYSTICK AP_SUBGROUPEXTENSION("", 63, SIM, var_sfml_joystick), #endif // SFML_JOYSTICK @@ -548,6 +553,11 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // user settable parameters for the barometers const AP_Param::GroupInfo SIM::BaroParm::var_info[] = { AP_GROUPINFO("RND", 1, SIM::BaroParm, noise, 0.2f), + // @Param: BARO_DRIFT + // @DisplayName: Baro altitude drift + // @Description: Barometer altitude drifts at this rate + // @Units: m/s + // @User: Advanced AP_GROUPINFO("DRIFT", 2, SIM::BaroParm, drift, 0), AP_GROUPINFO("DISABLE", 3, SIM::BaroParm, disable, 0), AP_GROUPINFO("GLITCH", 4, SIM::BaroParm, glitch, 0), @@ -1185,6 +1195,29 @@ const AP_Param::GroupInfo SIM::var_ins[] = { AP_GROUPEND }; +// user settable parameters for the physics models +const AP_Param::GroupInfo SIM::ModelParm::var_info[] = { + +#if AP_SIM_SHIP_ENABLED + // @Group: SHIP_ + // @Path: ./SIM_Ship.cpp + AP_SUBGROUPINFO(shipsim, "SHIP_", 1, SIM::ModelParm, ShipSim), +#endif +#if AP_SIM_STRATOBLIMP_ENABLED + // @Group: SB_ + // @Path: ./SIM_StratoBlimp.cpp + AP_SUBGROUPPTR(stratoblimp_ptr, "SB_", 2, SIM::ModelParm, StratoBlimp), +#endif + +#if AP_SIM_GLIDER_ENABLED + // @Group: GLD_ + // @Path: ./SIM_Glider.cpp + AP_SUBGROUPPTR(glider_ptr, "GLD_", 3, SIM::ModelParm, Glider), +#endif + + AP_GROUPEND +}; + const Location post_origin { 518752066, 146487830, @@ -1195,6 +1228,11 @@ const Location post_origin { /* report SITL state via MAVLink SIMSTATE*/ void SIM::simstate_send(mavlink_channel_t chan) const { + if (stop_MAVLink_sim_state) { + // Sim only MAVLink messages disabled to give more relaistic data rates + return; + } + float yaw; // convert to same conventions as DCM @@ -1220,6 +1258,11 @@ void SIM::simstate_send(mavlink_channel_t chan) const /* report SITL state via MAVLink SIM_STATE */ void SIM::sim_state_send(mavlink_channel_t chan) const { + if (stop_MAVLink_sim_state) { + // Sim only MAVLink messages disabled to give more relaistic data rates + return; + } + // convert to same conventions as DCM float yaw = state.yawDeg; if (yaw > 180) { diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 5198ba1f32b32..4d8beb2eddd9b 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -11,6 +11,7 @@ #include #include #include + #include "SIM_Buzzer.h" #include "SIM_Gripper_EPM.h" #include "SIM_Gripper_Servo.h" @@ -46,7 +47,9 @@ struct float_array { uint16_t length; float *data; }; - + +class StratoBlimp; +class Glider; struct sitl_fdm { // this is the structure passed between FDM models and the main SITL code @@ -60,8 +63,8 @@ struct sitl_fdm { double rollRate, pitchRate, yawRate; // degrees/s in body frame double rollDeg, pitchDeg, yawDeg; // euler angles, degrees Quaternion quaternion; - double airspeed; // m/s - Vector3f velocity_air_bf; // velocity relative to airmass, body frame + double airspeed; // m/s, EAS + Vector3f velocity_air_bf; // velocity relative to airmass, body frame, TAS double battery_voltage; // Volts double battery_current; // Amps double battery_remaining; // Ah, if non-zero capacity @@ -181,7 +184,6 @@ class SIM { AP_Int8 mag_orient[HAL_COMPASS_MAX_SENSORS]; // external compass orientation AP_Int8 mag_fail[HAL_COMPASS_MAX_SENSORS]; // fail magnetometer, 1 for no data, 2 for freeze AP_Int8 mag_save_ids; - AP_Float servo_speed; // servo speed in seconds AP_Float sonar_glitch;// probability between 0-1 that any given sonar sample will read as max distance AP_Float sonar_noise; // in metres @@ -294,6 +296,34 @@ class SIM { AP_Int8 signflip; }; AirspeedParm airspeed[AIRSPEED_MAX_SENSORS]; + + class ServoParams { + public: + ServoParams(void) { + AP_Param::setup_object_defaults(this, var_info); + } + static const struct AP_Param::GroupInfo var_info[]; + AP_Float servo_speed; // servo speed in seconds per 60 degrees + AP_Float servo_delay; // servo delay in seconds + AP_Float servo_filter; // servo 2p filter in Hz + }; + ServoParams servo; + + // physics model parameters + class ModelParm { + public: + static const struct AP_Param::GroupInfo var_info[]; +#if AP_SIM_STRATOBLIMP_ENABLED + StratoBlimp *stratoblimp_ptr; +#endif +#if AP_SIM_SHIP_ENABLED + ShipSim shipsim; +#endif +#if AP_SIM_GLIDER_ENABLED + Glider *glider_ptr; +#endif + }; + ModelParm models; // EFI type enum EFIType { @@ -443,11 +473,6 @@ class SIM { Sprayer sprayer_sim; - // simulated ship takeoffs -#if AP_SIM_SHIP_ENABLED - ShipSim shipsim; -#endif - Gripper_Servo gripper_sim; Gripper_EPM gripper_epm_sim; @@ -543,6 +568,11 @@ class SIM { AP_Int16 osd_rows; AP_Int16 osd_columns; #endif + + // Allow inhibiting of SITL only sim state messages over MAVLink + // This gives more realistic data rates for testing links + void set_stop_MAVLink_sim_state() { stop_MAVLink_sim_state = true; } + bool stop_MAVLink_sim_state; }; } // namespace SITL diff --git a/libraries/SITL/ServoModel.cpp b/libraries/SITL/ServoModel.cpp new file mode 100644 index 0000000000000..deaff68b70ae9 --- /dev/null +++ b/libraries/SITL/ServoModel.cpp @@ -0,0 +1,136 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simple model of a servo. Model is: + + - time delay for transport protocol delay + - slew limit + - 2-pole butterworth +*/ + +#include "ServoModel.h" +#include "SITL.h" + +// SITL servo model parameters +const AP_Param::GroupInfo SITL::SIM::ServoParams::var_info[] = { + // @Param: SPEED + // @DisplayName: servo speed + // @Description: servo speed (time for 60 degree deflection). If DELAY and FILTER are not set then this is converted to a 1p lowpass filter. If DELAY or FILTER are set then this is treated as a rate of change limit + // @Units: s + AP_GROUPINFO("SPEED", 1, ServoParams, servo_speed, 0.14), + + // @Param: DELAY + // @DisplayName: servo delay + // @Description: servo delay + // @Units: s + AP_GROUPINFO("DELAY", 2, ServoParams, servo_delay, 0.0), + + // @Param: FILTER + // @DisplayName: servo filter + // @Description: servo filter + // @Units: Hz + AP_GROUPINFO("FILTER", 3, ServoParams, servo_filter, 0), + + AP_GROUPEND +}; + +/* + simpler filter used when SIM_SERVO_FILTER and SIM_SERVO_DELAY are not set + this filter is a 1p low pass based on SIM_SERVO_SPEED + */ +float ServoModel::apply_simple_filter(float v, float dt) +{ + const auto *sitl = AP::sitl(); + if (!is_positive(sitl->servo.servo_speed)) { + return v; + } + const float cutoff = 1.0f / (2 * M_PI * sitl->servo.servo_speed); + filter1p.set_cutoff_frequency(cutoff); + return filter1p.apply(v, dt); +} + +/* + apply a filter for a servo model consistting of a delay, speed and 2p filter + */ +float ServoModel::apply_filter(float v, float dt) +{ + const auto *sitl = AP::sitl(); + if (!sitl) { + return v; + } + + if (!is_positive(sitl->servo.servo_delay) && + !is_positive(sitl->servo.servo_filter)) { + // fallback to a simpler 1p filter model + return apply_simple_filter(v, dt); + } + + // apply delay + if (sitl->servo.servo_delay > 0) { + uint32_t delay_len = MAX(1,sitl->servo.servo_delay * sitl->loop_rate_hz); + if (!delay) { + delay = new ObjectBuffer(); + } + if (delay->get_size() != delay_len) { + delay->set_size(delay_len); + } + while (delay->space() > 0) { + delay->push(v); + } + IGNORE_RETURN(delay->pop(v)); + } + + // apply slew limit + if (sitl->servo.servo_speed > 0) { + // assume SIM_SERVO_SPEED is time for 60 degrees + float time_per_degree = sitl->servo.servo_speed / 60.0; + float proportion_per_second = 1.0 / (angle_deg * time_per_degree); + delta_max = proportion_per_second * dt; + v = constrain_float(v, last_v-delta_max, last_v+delta_max); + v = constrain_float(v, -1, 1); + last_v = v; + } + + // apply filter + if (sitl->servo.servo_filter > 0) { + filter.set_cutoff_frequency(sitl->loop_rate_hz, sitl->servo.servo_filter); + v = filter.apply(v); + } + + return v; +} + +float ServoModel::filter_range(uint16_t pwm, float dt) +{ + const float v = (pwm - pwm_min)/float(pwm_max - pwm_min); + return apply_filter(v, dt); +} + +float ServoModel::filter_angle(uint16_t pwm, float dt) +{ + const float v = (pwm - 0.5*(pwm_max+pwm_min))/(0.5*float(pwm_max - pwm_min)); + return apply_filter(v, dt); +} + +void ServoModel::set_pwm_range(uint16_t _pwm_min, uint16_t _pwm_max) +{ + pwm_min = _pwm_min; + pwm_max = _pwm_max; +} + +void ServoModel::set_deflection(float _angle_deg) +{ + angle_deg = fabsf(_angle_deg); +} diff --git a/libraries/SITL/ServoModel.h b/libraries/SITL/ServoModel.h new file mode 100644 index 0000000000000..941f8a0312dc4 --- /dev/null +++ b/libraries/SITL/ServoModel.h @@ -0,0 +1,51 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simple model of a servo. Model is: + + - time delay for transport protocol delay + - slew limit + - 2-pole butterworth +*/ + +#include +#include +#include +#include + + +class ServoModel { +public: + float filter_angle(uint16_t pwm, float dt); + float filter_range(uint16_t pwm, float dt); + void set_pwm_range(uint16_t _pwm_min, uint16_t _pwm_max); + void set_deflection(float _angle_deg); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + float apply_filter(float v, float dt); + float apply_simple_filter(float v, float dt); + + LowPassFilter2pFloat filter; + LowPassFilterFloat filter1p; + ObjectBuffer *delay; + float last_v; + float delta_max; + uint16_t pwm_min = 1000; + uint16_t pwm_max = 2000; + float angle_deg = 45.0; +}; + diff --git a/libraries/SRV_Channel/SRV_Channels.cpp b/libraries/SRV_Channel/SRV_Channels.cpp index 7f01f8b14cfd9..54b86b0254384 100644 --- a/libraries/SRV_Channel/SRV_Channels.cpp +++ b/libraries/SRV_Channel/SRV_Channels.cpp @@ -474,6 +474,7 @@ void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value) } } +#if AP_SCRIPTING_ENABLED && AP_SCHEDULER_ENABLED // set output value for a specific function channel as a pwm value with loop based timeout // timeout_ms of zero will clear override of the channel // minimum override is 1 MAIN_LOOP @@ -499,6 +500,7 @@ void SRV_Channels::set_output_pwm_chan_timeout(uint8_t chan, uint16_t value, uin } } } +#endif // AP_SCRIPTING_ENABLED /* wrapper around hal.rcout->cork() diff --git a/modules/DroneCAN/DSDL b/modules/DroneCAN/DSDL index eb370f198f17e..993be80a62ec9 160000 --- a/modules/DroneCAN/DSDL +++ b/modules/DroneCAN/DSDL @@ -1 +1 @@ -Subproject commit eb370f198f17e561706d6eaddb02cb06d9e91cf6 +Subproject commit 993be80a62ec957c01fb41115b83663959a49f46 diff --git a/modules/mavlink b/modules/mavlink index 1e04d8b8634da..2825252d6d13e 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 1e04d8b8634dafc8c9a2496c6922e0749e00c009 +Subproject commit 2825252d6d13eb347520f028b3c580ab29bd78e5 diff --git a/modules/waf b/modules/waf index 1b1625b8e7da6..b25b5c7d98c50 160000 --- a/modules/waf +++ b/modules/waf @@ -1 +1 @@ -Subproject commit 1b1625b8e7da6e1307d73335cb995fa8813d5950 +Subproject commit b25b5c7d98c502b07976740b0a65b9f39948c292 diff --git a/wscript b/wscript index 5127c1b2df6e0..0517655459219 100644 --- a/wscript +++ b/wscript @@ -528,7 +528,6 @@ def configure(cfg): cfg.msg('Setting board to', cfg.options.board) cfg.get_board().configure(cfg) - cfg.load('clang_compilation_database') cfg.load('waf_unit_test') cfg.load('mavgen') cfg.load('dronecangen') @@ -657,6 +656,8 @@ def list_ap_periph_boards(ctx): def ap_periph_boards(ctx): return boards.get_ap_periph_boards() +vehicles = ['antennatracker', 'blimp', 'copter', 'heli', 'plane', 'rover', 'sub'] + def generate_tasklist(ctx, do_print=True): boardlist = boards.get_boards_names() ap_periph_targets = boards.get_ap_periph_boards() @@ -675,11 +676,11 @@ def generate_tasklist(ctx, do_print=True): task['targets'] = ['iofirmware', 'bootloader'] else: if boards.is_board_based(board, boards.sitl): - task['targets'] = ['antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub', 'replay'] + task['targets'] = vehicles + ['replay'] elif boards.is_board_based(board, boards.linux): - task['targets'] = ['antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub'] + task['targets'] = vehicles else: - task['targets'] = ['antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub', 'bootloader'] + task['targets'] = vehicles + ['bootloader'] task['buildOptions'] = '--upload' tasks.append(task) tlist.write(json.dumps(tasks)) @@ -901,7 +902,7 @@ ardupilotwaf.build_command('check-all', doc='shortcut for `waf check --alltests`', ) -for name in ('antennatracker', 'copter', 'heli', 'plane', 'rover', 'sub', 'blimp', 'bootloader','iofirmware','AP_Periph','replay'): +for name in (vehicles + ['bootloader','iofirmware','AP_Periph','replay']): ardupilotwaf.build_command(name, program_group_list=name, doc='builds %s programs' % name,