From c7217528b17a12a1e4ac2a4c2baa3689df137231 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Thu, 30 Jan 2025 16:44:23 +0530 Subject: [PATCH 01/85] AP_HAL_ChibiOS: fix incorrect definition of AP_PERIPH_MAG_ENABLED for Here4AP --- libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat index d5204764187105..47583886ac4a52 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat @@ -116,7 +116,7 @@ define HAL_COMPASS_MAX_SENSORS 1 define AP_PERIPH_GPS_ENABLED 1 -define AP_PERIPH_MAG_ENABLED 1 1 +define AP_PERIPH_MAG_ENABLED 1 define GPS_MOVING_BASELINE 1 define HAL_PERIPH_GPS_PORT_DEFAULT 3 From c4654c98286e21552503e3549b36675efca76cf5 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Thu, 30 Jan 2025 08:49:42 +0530 Subject: [PATCH 02/85] AP_HAL_ChibiOS: use AP_PERIPH_BARO_ENABLED in place of HAL_PERIPH_ENABLE_BRO --- libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat | 2 +- .../hwdef/CubeOrange-periph-heavy/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/mRoKitCANrevC/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 8 +++++++- 38 files changed, 44 insertions(+), 38 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat index 72c70c13be38e7..cc045994a16024 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -112,7 +112,7 @@ define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat index adbe684dc7c164..136a58e71e372d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat @@ -112,7 +112,7 @@ define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_BUZZER define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat index 8efb3966cedcdd..6d338b24b87240 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat @@ -124,7 +124,7 @@ define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_BUZZER define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat index 0fe5876f5e0fa5..1eab1882778ebe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat @@ -102,7 +102,7 @@ define HAL_COMPASS_MAX_SENSORS 1 define HAL_PERIPH_ENABLE_RC_OUT define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_BUZZER define HAL_PERIPH_NEOPIXEL_COUNT 8 define HAL_PERIPH_NEOPIXEL_CHAN 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat index 81c3a4d2382699..b0aa2d4737276d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat @@ -132,7 +132,7 @@ define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+Buzzer+NeoPixels define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # do direct neopixel LED output to enable the 'rainbow' effect on # startup diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat index 0f7c4f28d8e785..65b41673111c0a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat @@ -113,7 +113,7 @@ define HAL_NO_GCS define AP_PARAM_MAX_EMBEDDED_PARAM 512 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT # enable ESC control diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat index f69d78995c0827..4b2a9bf4dd5379 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat @@ -116,7 +116,7 @@ define HAL_NO_GCS define AP_PARAM_MAX_EMBEDDED_PARAM 512 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT # enable ESC control diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat index 55240ba00c83e4..b9f93dcece6178 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat @@ -26,7 +26,7 @@ env AP_PERIPH 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT 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 fcc4f21248c78c..0bdd71f6a82204 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat @@ -19,7 +19,7 @@ define AP_CAN_SLCAN_ENABLED 1 define AP_PERIPH_BATTERY_ENABLED 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_IMU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat index 2e12823414eac3..f577bcd34d2f79 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat @@ -19,7 +19,7 @@ define AP_CAN_SLCAN_ENABLED 1 define AP_PERIPH_BATTERY_ENABLED 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_IMU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat index 6d8c4a9ebc59be..8165621df8bab3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat @@ -124,7 +124,7 @@ define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+Buzzer+NeoPixels define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat index 47583886ac4a52..aaf6c00113d649 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat @@ -90,7 +90,7 @@ define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE -define HAL_PERIPH_ENABLE_BARO TRUE +define AP_PERIPH_BARO_ENABLED 1 SPIDEV rm3100 SPI3 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat index afccf9e322ddfe..2475d59785c8f6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat @@ -140,7 +140,7 @@ env ROMFS_UNCOMPRESSED True define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # septentrio on com 3 define HAL_GPS1_TYPE_DEFAULT 10 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat index 2f5cb43ec88e20..f9e7e762a2eef0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat @@ -143,7 +143,7 @@ define HAL_PERIPH_ENABLE_IMU # GPS+MAG+LEDs define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_IMU define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat index 6ecb29d8934311..a0deb7404843ce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat @@ -139,7 +139,7 @@ define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+LEDs define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat index 81d2f2ce43ba69..ccf11cb8932317 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat @@ -28,7 +28,7 @@ define AIRSPEED_MAX_SENSORS 1 # ----------- I2C Barometer -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_BARO_ALLOW_INIT_NO_BARO # BARO SPL06 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat index a8e2bab91d0749..33045cf9343bc3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat @@ -18,7 +18,7 @@ env AP_PERIPH 1 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED define HAL_PERIPH_ENABLE_ADSB define HAL_PERIPH_ENABLE_RANGEFINDER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat index 575f1861d00bb9..10636f8c16f0e0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat @@ -41,7 +41,7 @@ COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 # --------------------- Barometer --------------------------- -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_BARO_ALLOW_INIT_NO_BARO BARO SPL06 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat index 5ab040c8b3329f..d8d132ba8d36ac 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat @@ -96,7 +96,7 @@ define AP_PERIPH_MAG_ENABLED 1 define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_I2C_INTERNAL_MASK 0 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED # bootloader embedding / bootloader flashing not available diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat index 6df88261149a4c..85d0c1daf3b1ac 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat @@ -99,7 +99,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 512 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED BARO MS56XX SPI:ms5611 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat index 08114a20cca3c8..317c017ecc522d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat @@ -68,7 +68,7 @@ define AP_PERIPH_GPS_ENABLED 1 define HAL_PERIPH_GPS_PORT_DEFAULT 3 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define AP_PERIPH_BATTERY_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat index 8cbd900e6c1cb5..b36072399e4eaa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat @@ -91,7 +91,7 @@ define AP_RM3100_REVERSAL_MASK 7 define HAL_COMPASS_MAX_SENSORS 1 # --------------------- DPS310 --------------------------- -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ BARO DPS310 SPI:dps310 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat index c50ba5b1c874ad..ef6affc57cdbe3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat @@ -103,7 +103,7 @@ define HAL_COMPASS_MAX_SENSORS 1 define AP_PERIPH_GPS_ENABLED 1 define HAL_PERIPH_GPS_PORT_DEFAULT 3 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat index 3794a77a0d41a5..d719b80c10a041 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat @@ -114,7 +114,7 @@ define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+Buzzer+NeoPixels define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY define CONFIGURE_PPS_PIN TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat index 258c27f6fa3119..c789bc5a4f53e9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat @@ -110,7 +110,7 @@ define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+NeoPixels define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat index 740a59454681fa..9fae1fd5ce171c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavIC/hwdef.dat @@ -90,7 +90,7 @@ env ROMFS_UNCOMPRESSED True define AP_PERIPH_GPS_ENABLED 1 define GPS_MAX_RATE_MS 200 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # disable dual GPS and GPS blending to save flash space define GPS_MAX_RECEIVERS 1 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 2764f8f9b7b1d9..45e3d550e3cfde 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro-G4/hwdef.dat @@ -85,7 +85,7 @@ define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG+BARO+LEDs define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY 0 define HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY 8 define DEFAULT_NTF_LED_TYPES 455 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat index 75351254e6c1a5..9ce68a2696b2a7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat @@ -88,7 +88,7 @@ env ROMFS_UNCOMPRESSED True # enable GPS and compass define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat index 4a52289c9c1140..bf964a239480f1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -132,7 +132,7 @@ define HAL_BARO_ALLOW_INIT_NO_BARO define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # reduce the number of CAN RX Buffer define HAL_CAN_RX_QUEUE_SIZE 32 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat index 367832906db647..bb0c1f97978342 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat @@ -13,7 +13,7 @@ BARO DPS310 I2C:0:0x77 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 define HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # I2C Airspeed sensor must use a different address than 0x77 define HAL_PERIPH_ENABLE_AIRSPEED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat index 4f3716e2626dbf..d6056f2fcffbeb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat @@ -16,7 +16,7 @@ BARO DPS280 I2C:0:0x77 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 define HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # Optional I2C Airspeed sensor connected to I2C connector define HAL_PERIPH_ENABLE_AIRSPEED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index fd9550bf37258c..3aad3bfa13bb97 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -123,7 +123,7 @@ BARO DPS310 I2C:0:0x76 # also allow for airspeed on i2c port, and rangefinder on MSP port define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED define HAL_PERIPH_ENABLE_RANGEFINDER define HAL_PERIPH_ENABLE_MSP diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat index aac04b6822b424..ba9aaf55fc846e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat @@ -7,7 +7,7 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES # enable all features define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED define HAL_PERIPH_ENABLE_ADSB define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat index dd3aaf21f212b8..02d67155b26894 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat @@ -156,7 +156,7 @@ COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 # --------------------- DPS310 --------------------------- -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_BARO_ALLOW_INIT_NO_BARO BARO DPS310 I2C:0:0x76 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat index 82c206bfa60676..d1ade70103782f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRo-M10095/hwdef.dat @@ -50,7 +50,7 @@ PB7 I2C1_SDA I2C1 # an I2C baro (DPS310) BARO DPS280 I2C:0:0x77 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 PA0 VSENSE50 ADC1 SCALE(3) PA1 VSENSE3v3 ADC1 SCALE(2) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoKitCANrevC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoKitCANrevC/hwdef.dat index b5b5233e80e52d..8ee3e76cc3c801 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoKitCANrevC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoKitCANrevC/hwdef.dat @@ -19,7 +19,7 @@ BARO DPS310 I2C:0:0x77 define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 define HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 # I2C Airspeed sensor must use a different address than 0x77 define HAL_PERIPH_ENABLE_AIRSPEED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat index 69025f3ee3071f..a02b974f73d274 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/rGNSS/hwdef.dat @@ -116,7 +116,7 @@ define GPS_MOVING_BASELINE 1 # GPS+MAG+BARO+LEDs define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 -define HAL_PERIPH_ENABLE_BARO +define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index 35d6d0789041e1..a2cc8b797c9a21 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -175,6 +175,9 @@ #ifdef HAL_PERIPH_ENABLE_MAG #error "Change 'define HAL_PERIPH_ENABLE_MAG' to 'define AP_PERIPH_MAG_ENABLED 1'" #endif +#ifdef HAL_PERIPH_ENABLE_BARO +#error "Change 'define HAL_PERIPH_ENABLE_BARO' to 'define AP_PERIPH_BARO_ENABLED 1'" +#endif /* * defaults for various AP_Periph features: @@ -194,6 +197,9 @@ #ifndef AP_PERIPH_MAG_ENABLED #define AP_PERIPH_MAG_ENABLED 0 #endif +#ifndef AP_PERIPH_BARO_ENABLED +#define AP_PERIPH_BARO_ENABLED 0 +#endif /* * turning on of ArduPilot features based on which AP_Periph features @@ -203,6 +209,7 @@ #define AP_GPS_ENABLED AP_PERIPH_GPS_ENABLED #define AP_AHRS_ENABLED AP_PERIPH_AHRS_ENABLED #define AP_COMPASS_ENABLED AP_PERIPH_MAG_ENABLED +#define AP_BARO_ENABLED AP_PERIPH_BARO_ENABLED /* * GPS Backends - we selectively turn backends on. @@ -388,7 +395,6 @@ #define AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED 0 #endif -#define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO) #define AP_RANGEFINDER_ENABLED defined(HAL_PERIPH_ENABLE_RANGEFINDER) #define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM) #define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN) From 4fca0ccd0b4e22d30f251d6a0b3f8aad628820b5 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Thu, 30 Jan 2025 08:50:10 +0530 Subject: [PATCH 03/85] AP_Scripting: use AP_PERIPH_BARO_ENABLED in place of HAL_PERIPH_ENABLE_BRO --- libraries/AP_Scripting/generator/description/bindings.desc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 9b9a931e733f5c..856097a9be470c 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -429,7 +429,7 @@ singleton serial manual find_serial lua_serial_find_serial 1 1 singleton serial manual find_simulated_device lua_serial_find_simulated_device 2 1 depends AP_SCRIPTING_SERIALDEVICE_ENABLED include AP_Baro/AP_Baro.h -singleton AP_Baro depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BARO)) +singleton AP_Baro depends AP_BARO_ENABLED singleton AP_Baro rename baro singleton AP_Baro method get_pressure float singleton AP_Baro method get_temperature float From dba4136f95b9ebc84ff3c6224c66c8489da0452c Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Thu, 30 Jan 2025 08:50:47 +0530 Subject: [PATCH 04/85] Tools: create and use AP_PERIPH_BARO_ENABLED --- Tools/AP_Periph/AP_Periph.cpp | 4 ++-- Tools/AP_Periph/AP_Periph.h | 4 ++-- Tools/AP_Periph/Parameters.cpp | 2 +- Tools/AP_Periph/Parameters.h | 2 +- Tools/AP_Periph/baro.cpp | 4 ++-- Tools/AP_Periph/can.cpp | 4 ++-- Tools/AP_Periph/msp.cpp | 6 +++--- Tools/ardupilotwaf/boards.py | 2 +- 8 files changed, 14 insertions(+), 14 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 3091751f0a1547..4175c4d3deec19 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -164,7 +164,7 @@ void AP_Periph_FW::init() compass.init(); #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED baro.init(); #endif @@ -429,7 +429,7 @@ void AP_Periph_FW::update() const Vector3f &field = compass.get_field(); hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z)); #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED 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 diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 4faed8e5bf18dd..9ae4ed478e1925 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -231,7 +231,7 @@ class AP_Periph_FW { Compass compass; #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED AP_Baro baro; #endif @@ -457,7 +457,7 @@ class AP_Periph_FW { uint32_t last_gps_yaw_ms; #endif uint32_t last_relposheading_ms; -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED uint32_t last_baro_update_ms; #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index e9f9b54f269941..f9d51fd1f9481e 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -269,7 +269,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(compass, "COMPASS_", Compass), #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED // Baro driver // @Group: BARO // @Path: ../libraries/AP_Baro/AP_Baro.cpp diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 56340380345bd3..6bafab4b1e901b 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -119,7 +119,7 @@ class Parameters { #ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY AP_Int8 led_brightness; #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED AP_Int8 baro_enable; #endif #if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT) diff --git a/Tools/AP_Periph/baro.cpp b/Tools/AP_Periph/baro.cpp index 61c296cd137fd5..a4f089d633597b 100644 --- a/Tools/AP_Periph/baro.cpp +++ b/Tools/AP_Periph/baro.cpp @@ -1,6 +1,6 @@ #include "AP_Periph.h" -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED /* barometer support @@ -60,4 +60,4 @@ void AP_Periph_FW::can_baro_update(void) } } -#endif // HAL_PERIPH_ENABLE_BARO +#endif // AP_PERIPH_BARO_ENABLED diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 5705b4e2b0200e..4537eb87db9367 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -355,7 +355,7 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C #if AP_PERIPH_MAG_ENABLED AP_Param::setup_object_defaults(&compass, compass.var_info); #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED AP_Param::setup_object_defaults(&baro, baro.var_info); #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED @@ -1894,7 +1894,7 @@ void AP_Periph_FW::can_update() #if AP_PERIPH_BATTERY_ENABLED can_battery_update(); #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED can_baro_update(); #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED diff --git a/Tools/AP_Periph/msp.cpp b/Tools/AP_Periph/msp.cpp index 3d89eedc55adad..e2a1a00e75fa6a 100644 --- a/Tools/AP_Periph/msp.cpp +++ b/Tools/AP_Periph/msp.cpp @@ -48,7 +48,7 @@ void AP_Periph_FW::msp_sensor_update(void) #if AP_PERIPH_GPS_ENABLED send_msp_GPS(); #endif -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED send_msp_baro(); #endif #if AP_PERIPH_MAG_ENABLED @@ -125,7 +125,7 @@ void AP_Periph_FW::send_msp_GPS(void) #endif // AP_PERIPH_GPS_ENABLED -#ifdef HAL_PERIPH_ENABLE_BARO +#if AP_PERIPH_BARO_ENABLED /* send MSP baro packet */ @@ -149,7 +149,7 @@ void AP_Periph_FW::send_msp_baro(void) send_msp_packet(MSP2_SENSOR_BAROMETER, &p, sizeof(p)); } -#endif // HAL_PERIPH_ENABLE_BARO +#endif // AP_PERIPH_BARO_ENABLED #if AP_PERIPH_MAG_ENABLED /* diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 79d8d4aa05ac37..1d1100f759b63c 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -955,7 +955,7 @@ def configure_env(self, cfg, env): AP_PERIPH_GPS_ENABLED = 1, HAL_PERIPH_ENABLE_AIRSPEED = 1, AP_PERIPH_MAG_ENABLED = 1, - HAL_PERIPH_ENABLE_BARO = 1, + AP_PERIPH_BARO_ENABLED = 1, HAL_PERIPH_ENABLE_IMU = 1, HAL_PERIPH_ENABLE_RANGEFINDER = 1, AP_PERIPH_BATTERY_ENABLED = 1, From 061f3825a7ed76854536a155dd6fb54eede865ac Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 17:44:40 +1100 Subject: [PATCH 05/85] AP_Logger: use GCS_SEND_TEXT for error message rather than stdout This one is line noise before this patch: Failed to create log directory /APM/LOGS : ENOSPC --- libraries/AP_Logger/AP_Logger_File.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index e32d293fa76215..07e417d19a390c 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -67,7 +67,7 @@ void AP_Logger_File::ensure_log_directory_exists() ret = AP::FS().mkdir(_log_directory); } if (ret == -1 && errno != EEXIST) { - printf("Failed to create log directory %s : %s\n", _log_directory, strerror(errno)); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to create log directory %s : %s", _log_directory, strerror(errno)); } } From 97e87dfcdbabcb85706b76381fde62a6ebccfcbc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 11:52:24 +1100 Subject: [PATCH 06/85] AP_HAL_ChibiOS: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL_ChibiOS/I2CDevice.cpp | 15 +++++++-------- libraries/AP_HAL_ChibiOS/I2CDevice.h | 10 ++++++---- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp index 12bead827bdcbb..c5cec1730dea94 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.cpp +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.cpp @@ -449,18 +449,17 @@ bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint3 return bus.adjust_timer(h, period_usec); } -AP_HAL::OwnPtr -I2CDeviceManager::get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock, - bool use_smbus, - uint32_t timeout_ms) +AP_HAL::I2CDevice * +I2CDeviceManager::get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock, + bool use_smbus, + uint32_t timeout_ms) { bus -= HAL_I2C_BUS_BASE; if (bus >= ARRAY_SIZE(I2CD)) { - return AP_HAL::OwnPtr(nullptr); + return nullptr; } - auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); - return dev; + return NEW_NOTHROW I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms); } /* diff --git a/libraries/AP_HAL_ChibiOS/I2CDevice.h b/libraries/AP_HAL_ChibiOS/I2CDevice.h index 143fe29f1d7ed9..487646576398c5 100644 --- a/libraries/AP_HAL_ChibiOS/I2CDevice.h +++ b/libraries/AP_HAL_ChibiOS/I2CDevice.h @@ -126,10 +126,12 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager { return static_cast(i2c_mgr); } - AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock=400000, - bool use_smbus = false, - uint32_t timeout_ms=4) override; + /* Get a pointer to a newly-allocated I2CDevice handle. Lifetime + * is externally handled */ + AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock=400000, + bool use_smbus = false, + uint32_t timeout_ms=4) override; /* get mask of bus numbers for all configured I2C buses From 45db7d2231f1573081e6a35195901f2cbf2384ab Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 11:52:24 +1100 Subject: [PATCH 07/85] AP_HAL_Empty: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL_Empty/I2CDevice.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_Empty/I2CDevice.h b/libraries/AP_HAL_Empty/I2CDevice.h index 7f51e85ce00cde..bc2421e72a97bc 100644 --- a/libraries/AP_HAL_Empty/I2CDevice.h +++ b/libraries/AP_HAL_Empty/I2CDevice.h @@ -83,10 +83,10 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager { I2CDeviceManager() { } /* AP_HAL::I2CDeviceManager implementation */ - AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock=400000, - bool use_smbus = false, - uint32_t timeout_ms=4) override + AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock=400000, + bool use_smbus = false, + uint32_t timeout_ms=4) override { return nullptr; } From 0a617b500bb9780152cf94709939022192731535 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 11:52:24 +1100 Subject: [PATCH 08/85] AP_HAL: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL/I2CDevice.h | 20 +++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL/I2CDevice.h b/libraries/AP_HAL/I2CDevice.h index 1f6e6cf5b4352b..6659a28ffd5a33 100644 --- a/libraries/AP_HAL/I2CDevice.h +++ b/libraries/AP_HAL/I2CDevice.h @@ -70,11 +70,21 @@ class I2CDevice : public Device { class I2CDeviceManager { public: - /* Get a device handle */ - virtual OwnPtr get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock=400000, - bool use_smbus = false, - uint32_t timeout_ms=4) = 0; + /* Get a pointer to a newly-allocated I2CDevice handle. Lifetime + * is externally handled */ + virtual AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock=400000, + bool use_smbus = false, + uint32_t timeout_ms=4) = 0; + /* Get a device handle. Lifetime is handled by OwnPtr system. + * Progressively being eliminated */ + OwnPtr get_device(uint8_t bus, uint8_t address, + uint32_t bus_clock=400000, + bool use_smbus = false, + uint32_t timeout_ms=4) { + return AP_HAL::OwnPtr(get_device_ptr(bus, address, bus_clock, use_smbus, timeout_ms)); + } +; /* get mask of bus numbers for all configured I2C buses */ From 07d5938d68b17420f762333bf22192b04f5e26fa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 11:52:24 +1100 Subject: [PATCH 09/85] AP_HAL_Linux: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL_Linux/I2CDevice.cpp | 14 +++++++------- libraries/AP_HAL_Linux/I2CDevice.h | 10 +++++----- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_Linux/I2CDevice.cpp b/libraries/AP_HAL_Linux/I2CDevice.cpp index 0418e2fcc9881a..192388cc50e8af 100644 --- a/libraries/AP_HAL_Linux/I2CDevice.cpp +++ b/libraries/AP_HAL_Linux/I2CDevice.cpp @@ -280,11 +280,11 @@ I2CDeviceManager::I2CDeviceManager() _buses.reserve(4); } -AP_HAL::OwnPtr -I2CDeviceManager::get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock, - bool use_smbus, - uint32_t timeout_ms) +AP_HAL::I2CDevice * +I2CDeviceManager::get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock, + bool use_smbus, + uint32_t timeout_ms) { for (uint8_t i = 0, n = _buses.size(); i < n; i++) { if (_buses[i]->bus == bus) { @@ -313,10 +313,10 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address, } /* Create a new device increasing the bus reference */ -AP_HAL::OwnPtr +AP_HAL::I2CDevice * I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const { - auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(b, address)); + auto *dev = NEW_NOTHROW I2CDevice(b, address); if (!dev) { return nullptr; } diff --git a/libraries/AP_HAL_Linux/I2CDevice.h b/libraries/AP_HAL_Linux/I2CDevice.h index 92c57c2534f00e..73b049731389fe 100644 --- a/libraries/AP_HAL_Linux/I2CDevice.h +++ b/libraries/AP_HAL_Linux/I2CDevice.h @@ -95,10 +95,10 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager { I2CDeviceManager(); /* AP_HAL::I2CDeviceManager implementation */ - AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock=400000, - bool use_smbus = false, - uint32_t timeout_ms=4) override; + AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock=400000, + bool use_smbus = false, + uint32_t timeout_ms=4) override; /* * Stop all I2C threads and block until they are finalized. This doesn't @@ -124,7 +124,7 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager { protected: void _unregister(I2CBus &b); - AP_HAL::OwnPtr _create_device(I2CBus &b, uint8_t address) const; + AP_HAL::I2CDevice *_create_device(I2CBus &b, uint8_t address) const; std::vector _buses; }; From 049ad3928dfe597db3010f7207956373f4f6e090 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 11:52:24 +1100 Subject: [PATCH 10/85] AP_HAL_QURT: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL_QURT/I2CDevice.cpp | 15 +++++++-------- libraries/AP_HAL_QURT/I2CDevice.h | 2 +- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/libraries/AP_HAL_QURT/I2CDevice.cpp b/libraries/AP_HAL_QURT/I2CDevice.cpp index 0d5317f3f27ca6..971b0fb1f3c6bf 100644 --- a/libraries/AP_HAL_QURT/I2CDevice.cpp +++ b/libraries/AP_HAL_QURT/I2CDevice.cpp @@ -98,17 +98,16 @@ bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint3 return bus.adjust_timer(h, period_usec); } -AP_HAL::OwnPtr -I2CDeviceManager::get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock, - bool use_smbus, - uint32_t timeout_ms) +AP_HAL::I2CDevice * +I2CDeviceManager::get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock, + bool use_smbus, + uint32_t timeout_ms) { if (bus >= ARRAY_SIZE(i2c_bus_ids)) { - return AP_HAL::OwnPtr(nullptr); + return nullptr; } - auto dev = AP_HAL::OwnPtr(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); - return dev; + return new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms); } /* diff --git a/libraries/AP_HAL_QURT/I2CDevice.h b/libraries/AP_HAL_QURT/I2CDevice.h index 4e1c44e8f0130c..56a02c9b432688 100644 --- a/libraries/AP_HAL_QURT/I2CDevice.h +++ b/libraries/AP_HAL_QURT/I2CDevice.h @@ -111,7 +111,7 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager return static_cast(i2c_mgr); } - AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, + AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, uint32_t bus_clock=100000, bool use_smbus = false, uint32_t timeout_ms=4) override; From 51d1cee5eb417d66ad28026bd04a9b607967876c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 11:52:24 +1100 Subject: [PATCH 11/85] AP_HAL_SITL: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL_SITL/I2CDevice.cpp | 17 ++++++++--------- libraries/AP_HAL_SITL/I2CDevice.h | 8 ++++---- 2 files changed, 12 insertions(+), 13 deletions(-) diff --git a/libraries/AP_HAL_SITL/I2CDevice.cpp b/libraries/AP_HAL_SITL/I2CDevice.cpp index 28c1f11e4073e7..e0a59f0b802c28 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.cpp +++ b/libraries/AP_HAL_SITL/I2CDevice.cpp @@ -106,18 +106,17 @@ I2CDeviceManager::I2CDeviceManager() } } -AP_HAL::OwnPtr -I2CDeviceManager::get_device(uint8_t bus, - uint8_t address, - uint32_t bus_clock, - bool use_smbus, - uint32_t timeout_ms) +AP_HAL::I2CDevice * +I2CDeviceManager::get_device_ptr(uint8_t bus, + uint8_t address, + uint32_t bus_clock, + bool use_smbus, + uint32_t timeout_ms) { if (bus >= ARRAY_SIZE(buses)) { - return AP_HAL::OwnPtr(nullptr); + return nullptr; } - auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(buses[bus], address)); - return dev; + return NEW_NOTHROW I2CDevice(buses[bus], address); } void I2CDeviceManager::_timer_tick() diff --git a/libraries/AP_HAL_SITL/I2CDevice.h b/libraries/AP_HAL_SITL/I2CDevice.h index 828fd3efd48a85..c9a87fa2628c33 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.h +++ b/libraries/AP_HAL_SITL/I2CDevice.h @@ -118,10 +118,10 @@ class HALSITL::I2CDeviceManager : public AP_HAL::I2CDeviceManager { void _timer_tick(); // in lieu of a thread-per-bus /* AP_HAL::I2CDeviceManager implementation */ - AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock=400000, - bool use_smbus = false, - uint32_t timeout_ms=4) override; + AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock=400000, + bool use_smbus = false, + uint32_t timeout_ms=4) override; protected: From d5922b2cf11369e1abc6e708a477a7e18b394662 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 10:24:45 +1100 Subject: [PATCH 12/85] AP_Notify: avoid use of OwnPtr for ToshibaLED --- libraries/AP_Notify/ToshibaLED_I2C.cpp | 2 +- libraries/AP_Notify/ToshibaLED_I2C.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Notify/ToshibaLED_I2C.cpp b/libraries/AP_Notify/ToshibaLED_I2C.cpp index cfacbbd1e9b2b5..cbc502e833c783 100644 --- a/libraries/AP_Notify/ToshibaLED_I2C.cpp +++ b/libraries/AP_Notify/ToshibaLED_I2C.cpp @@ -49,7 +49,7 @@ ToshibaLED_I2C::ToshibaLED_I2C(uint8_t bus) bool ToshibaLED_I2C::init(void) { // first look for led on external bus - _dev = std::move(hal.i2c_mgr->get_device(_bus, TOSHIBA_LED_I2C_ADDR)); + _dev = hal.i2c_mgr->get_device_ptr(_bus, TOSHIBA_LED_I2C_ADDR); if (!_dev) { return false; } diff --git a/libraries/AP_Notify/ToshibaLED_I2C.h b/libraries/AP_Notify/ToshibaLED_I2C.h index c82e77986f5114..eecf6afe2816f5 100644 --- a/libraries/AP_Notify/ToshibaLED_I2C.h +++ b/libraries/AP_Notify/ToshibaLED_I2C.h @@ -27,12 +27,13 @@ class ToshibaLED_I2C : public RGBLed { public: ToshibaLED_I2C(uint8_t bus); + ~ToshibaLED_I2C() { delete _dev; } bool init(void) override; protected: bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) override; private: - AP_HAL::OwnPtr _dev; + AP_HAL::I2CDevice *_dev; void _timer(void); bool _need_update; struct { From 46973652d4df84caa57da83434e08c2fbfd81ce2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 17:20:44 +1100 Subject: [PATCH 13/85] AP_HAL_ESP32: add get_device_ptr to HAL I2CDevice API --- libraries/AP_HAL_ESP32/I2CDevice.cpp | 15 +++++++-------- libraries/AP_HAL_ESP32/I2CDevice.h | 2 +- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/libraries/AP_HAL_ESP32/I2CDevice.cpp b/libraries/AP_HAL_ESP32/I2CDevice.cpp index e2bcc9071ec81f..1d31619a43713d 100644 --- a/libraries/AP_HAL_ESP32/I2CDevice.cpp +++ b/libraries/AP_HAL_ESP32/I2CDevice.cpp @@ -150,17 +150,16 @@ bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint3 return bus.adjust_timer(h, period_usec); } -AP_HAL::OwnPtr -I2CDeviceManager::get_device(uint8_t bus, uint8_t address, - uint32_t bus_clock, - bool use_smbus, - uint32_t timeout_ms) +AP_HAL::I2CDevice * +I2CDeviceManager::get_device_ptr(uint8_t bus, uint8_t address, + uint32_t bus_clock, + bool use_smbus, + uint32_t timeout_ms) { if (bus >= ARRAY_SIZE(i2c_bus_desc)) { - return AP_HAL::OwnPtr(nullptr); + return nullptr; } - auto dev = AP_HAL::OwnPtr(NEW_NOTHROW I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms)); - return dev; + return NEW_NOTHROW I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms); } /* diff --git a/libraries/AP_HAL_ESP32/I2CDevice.h b/libraries/AP_HAL_ESP32/I2CDevice.h index 099de86d33bfe2..3119f18d709f50 100644 --- a/libraries/AP_HAL_ESP32/I2CDevice.h +++ b/libraries/AP_HAL_ESP32/I2CDevice.h @@ -124,7 +124,7 @@ class I2CDeviceManager : public AP_HAL::I2CDeviceManager return static_cast(i2c_mgr); } - AP_HAL::OwnPtr get_device(uint8_t bus, uint8_t address, + AP_HAL::I2CDevice *get_device_ptr(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus = false, uint32_t timeout_ms=4) override; From 2ef98e18ce2742e05578934192cf0e1ce8d6e2b0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 31 Jan 2025 08:27:38 +1100 Subject: [PATCH 14/85] Tools: size_compare_branches.py: mark navigator64 as a Linux board ... so we don't try to buld bootloaders for it --- Tools/scripts/size_compare_branches.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index b52e49f2991ae3..1e78630c409259 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -170,6 +170,7 @@ def linux_board_names(self): # grep 'class.*[(]linux' Tools/ardupilotwaf/boards.py | perl -pe "s/class (.*)\(linux\).*/ '\\1',/" return [ 'navigator', + 'navigator64', 'erleboard', 'navio', 'navio2', From c3f2b4013f69e54da67dbfb1d5a95e445b331cac Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 13:04:30 +1100 Subject: [PATCH 15/85] Copter: free allocations in case of allocation failure these would be leaked if the "new" call for the ModeGuidedCustom object failed. Since resgister_custom_mode may be called multiple times we could leak memory continuously --- ArduCopter/Copter.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 0b55d48e688e13..43c6d2bb759f40 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -451,6 +451,8 @@ AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, c } if (mode_guided_custom[i] == nullptr) { // Allocation failure + free((void*)full_name_copy); + free((void*)short_name_copy); return nullptr; } From 6bf29eca700120153d7404af1f397c2979715427 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 13:35:28 +1100 Subject: [PATCH 16/85] AP_AIS: remove incorrect use of strncat the third argument is space remaining in buffer, not size of buffer... ../../libraries/AP_AIS/AP_AIS.cpp:183:71: warning: Potential buffer overflow. Replace with 'sizeof(multi) - strlen(multi) - 1' or use a safer 'strlcat' API [unix.cstring.BadSizeArg] strncat(multi,_AIVDM_buffer[msg_parts[i]].payload,sizeof(multi)); ^~~~~~~~~~~~~ ../../libraries/AP_AIS/AP_AIS.cpp:185:49: warning: Potential buffer overflow. Replace with 'sizeof(multi) - strlen(multi) - 1' or use a safer 'strlcat' API [unix.cstring.BadSizeArg] strncat(multi,_incoming.payload,sizeof(multi)); --- libraries/AP_AIS/AP_AIS.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index afb141ec5356a9..0523267ac587cc 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -32,6 +32,7 @@ #include #include #include +#include const AP_Param::GroupInfo AP_AIS::var_info[] = { @@ -177,14 +178,14 @@ void AP_AIS::update() } // combine packets - char multi[AIVDM_PAYLOAD_SIZE*_incoming.total]; - strncpy(multi,_AIVDM_buffer[msg_parts[0]].payload,AIVDM_PAYLOAD_SIZE); + ExpandingString s; + s.append(_AIVDM_buffer[msg_parts[0]].payload, strlen(_AIVDM_buffer[msg_parts[0]].payload)); for (uint8_t i = 1; i < _incoming.total - 1; i++) { - strncat(multi,_AIVDM_buffer[msg_parts[i]].payload,sizeof(multi)); + s.append(_AIVDM_buffer[msg_parts[i]].payload, strlen(_AIVDM_buffer[msg_parts[i]].payload)); } - strncat(multi,_incoming.payload,sizeof(multi)); + s.append(_incoming.payload, strlen(_incoming.payload)); #if HAL_LOGGING_ENABLED - const bool decoded = payload_decode(multi); + const bool decoded = payload_decode(s.get_string()); #endif for (uint8_t i = 0; i < _incoming.total; i++) { #if HAL_LOGGING_ENABLED From 63afcae8a728675a06d87ff3bb5d467604cdcce9 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 30 Jan 2025 19:34:58 -0600 Subject: [PATCH 17/85] AP_Filesystem: ROMFS: fix open race conditions Lua opens scripts to load them into memory, then the logger opens them after to stream them into the dataflash log. When loading multiple large Lua scripts from ROMFS, decompression takes a significant amount of time. This creates the opportunity for the Lua interpreter and logging threads to both be inside `AP_Filesystem_ROMFS::open()` decompressing a file. If this happens, the function can return the same `fd` for two different calls as the `fd` is chosen before decompression starts, but only marked as being used after that finishes. The read pointers then stomp on each other, so Lua loads garbled scripts (usually resulting in a syntax error) and the logger dumps garbled data. Fix the issue by locking before searching for a free record (or marking a record as free). Apply the same fix to directories as well. This doesn't protect against using the same `fd`/`dirp` from multiple threads, but that behavior is to be discouraged anyway and is not the root cause here. --- libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp | 11 +++++++---- libraries/AP_Filesystem/AP_Filesystem_ROMFS.h | 5 +++++ 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp index f481d872558e5c..d4eca8812fb82f 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp @@ -32,6 +32,8 @@ int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_ errno = EROFS; return -1; } + + WITH_SEMAPHORE(record_sem); // search for free file record uint8_t idx; for (idx=0; idx + #include "AP_Filesystem_backend.h" class AP_Filesystem_ROMFS : public AP_Filesystem_Backend @@ -56,6 +58,9 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend void unload_file(FileData *fd) override; private: + // protect searching for free file/dir records when opening/closing + HAL_Semaphore record_sem; + // only allow up to 4 files at a time static constexpr uint8_t max_open_file = 4; static constexpr uint8_t max_open_dir = 4; From 4e35eb3673944850a2eba113e1b127a070a35b67 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 14:46:33 +1100 Subject: [PATCH 18/85] SITL: fix array-bounds warning in tsys01 sim ... if the driver ever asked for prom0 then we would do Very Bad Things here. File: build/sitl/../../libraries/SITL/SIM_Temperature_TSYS01.cpp Warning: line 38, column 13 Assigned value is garbage or undefined --- libraries/SITL/SIM_Temperature_TSYS01.cpp | 19 +++++++++++-------- libraries/SITL/SIM_Temperature_TSYS01.h | 3 ++- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/libraries/SITL/SIM_Temperature_TSYS01.cpp b/libraries/SITL/SIM_Temperature_TSYS01.cpp index 68f5f55e332605..949d7f266776d7 100644 --- a/libraries/SITL/SIM_Temperature_TSYS01.cpp +++ b/libraries/SITL/SIM_Temperature_TSYS01.cpp @@ -6,7 +6,7 @@ #include -constexpr const int32_t SITL::TSYS01::_k[5]; +constexpr const int32_t SITL::TSYS01::_k[6]; int SITL::TSYS01::rdwr(I2C::i2c_rdwr_ioctl_data *&data) { @@ -34,7 +34,7 @@ int SITL::TSYS01::rdwr(I2C::i2c_rdwr_ioctl_data *&data) if (data->msgs[1].len != 2) { AP_HAL::panic("Unexpected prom read length"); } - uint8_t offs = 5-((uint8_t(command) - uint8_t(Command::READ_PROM0))/2); + uint8_t offs = ARRAY_SIZE(_k)-((uint8_t(command) - uint8_t(Command::READ_PROM0))/2); const uint16_t k = _k[offs]; data->msgs[1].buf[0] = k >> 8; data->msgs[1].buf[1] = k & 0xFF; @@ -109,13 +109,16 @@ int SITL::TSYS01::rdwr(I2C::i2c_rdwr_ioctl_data *&data) float SITL::TSYS01::temperature_for_adc(uint32_t _adc) const { const float adc16 = _adc/256.0; - // const uint32_t _k[] { 28446, 24926, 36016, 32791, 40781 }; + // Note that the offsets used here start from 1 (PROM1), not like + // in the main codebase where they start from 0 (PROM1)! The main + // code does not read PROM0 from the device (real or simulated), + // but the array in the simulator here reserves a space for it. return - -2 * _k[4] * powf(10, -21) * powf(adc16, 4) + - 4 * _k[3] * powf(10, -16) * powf(adc16, 3) + - -2 * _k[2] * powf(10, -11) * powf(adc16, 2) + - 1 * _k[1] * powf(10, -6) * adc16 + - -1.5 * _k[0] * powf(10, -2); + -2 * _k[5] * powf(10, -21) * powf(adc16, 4) + + 4 * _k[4] * powf(10, -16) * powf(adc16, 3) + + -2 * _k[3] * powf(10, -11) * powf(adc16, 2) + + 1 * _k[2] * powf(10, -6) * adc16 + + -1.5 * _k[1] * powf(10, -2); } uint32_t SITL::TSYS01::calculate_adc(float temperature) const diff --git a/libraries/SITL/SIM_Temperature_TSYS01.h b/libraries/SITL/SIM_Temperature_TSYS01.h index 8b7127d0a17db2..273681592651ec 100644 --- a/libraries/SITL/SIM_Temperature_TSYS01.h +++ b/libraries/SITL/SIM_Temperature_TSYS01.h @@ -63,7 +63,8 @@ class TSYS01 : public I2CDevice READ_ADC = 0x00, }; - static constexpr int32_t _k[] { 40781, 32791, 36016, 24926, 28446 }; + // _k[0] is unused + static constexpr int32_t _k[] { 0, 40781, 32791, 36016, 24926, 28446 }; }; } // namespace SITL From 46d99a47f74b3bc04f8c246123e4b392021813ce Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Jan 2025 12:56:51 +1100 Subject: [PATCH 19/85] HAL_ChibiOS: support LSE for clock on STM32L4xx this allows for lower pin count devices with CAN --- .../hwdef/common/stm32l4_mcuconf.h | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h index eccaa7551a9b5c..ba747c06181853 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32l4_mcuconf.h @@ -32,6 +32,18 @@ #define STM32_PLLM_VALUE 2 #define STM32_PLLSRC STM32_PLLSRC_HSI16 +#elif STM32_HSECLK == 32768U +// low speed external oscillator +#define STM32_LSE_ENABLED TRUE +#define STM32_HSE_ENABLED FALSE +#define STM32_HSI16_ENABLED FALSE +#define STM32_MSI_ENABLED TRUE +#define STM32_PLLM_VALUE 1 +#define STM32_PLLN_VALUE 40 +#define STM32_PLLSAI1N_VALUE 24 +#define STM32_PLLSRC STM32_PLLSRC_MSI +#define STM32_MSIPLL_ENABLED TRUE + #elif STM32_HSECLK == 8000000U #define STM32_HSE_ENABLED TRUE #define STM32_HSI16_ENABLED FALSE @@ -72,8 +84,12 @@ #define STM32_PLS STM32_PLS_LEV0 #define STM32_HSI48_ENABLED FALSE #define STM32_LSI_ENABLED FALSE +#ifndef STM32_LSE_ENABLED #define STM32_LSE_ENABLED FALSE +#endif +#ifndef STM32_MSIPLL_ENABLED #define STM32_MSIPLL_ENABLED FALSE +#endif #define STM32_MSIRANGE STM32_MSIRANGE_4M #define STM32_MSISRANGE STM32_MSISRANGE_4M #define STM32_SW STM32_SW_PLL From 0679282ce2f503f5ac93522279add584c5077c1a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Jan 2025 13:09:05 +1100 Subject: [PATCH 20/85] AP_Bootloader: support CAN termination switch and LED --- Tools/AP_Bootloader/can.cpp | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/Tools/AP_Bootloader/can.cpp b/Tools/AP_Bootloader/can.cpp index 4ad70e951cb67d..dc5a25516ba0f3 100644 --- a/Tools/AP_Bootloader/can.cpp +++ b/Tools/AP_Bootloader/can.cpp @@ -836,6 +836,35 @@ void can_start() if (stm32_was_watchdog_reset()) { node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_WATCHDOG); } + + { + /* + support termination solder bridge or switch and optional LED + */ +#if defined(HAL_GPIO_PIN_GPIO_CAN1_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH) + const bool can1_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH); + palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, can1_term); +# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_LED + palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_LED, can1_term? HAL_LED_ON : !HAL_LED_ON); +# endif +#endif + +#if defined(HAL_GPIO_PIN_GPIO_CAN2_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH) + const bool can2_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH); + palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, can2_term); +# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_LED + palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_LED, can2_term? HAL_LED_ON : !HAL_LED_ON); +# endif +#endif + +#if defined(HAL_GPIO_PIN_GPIO_CAN3_TERM) && defined(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH) + const bool can3_term = palReadLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH); + palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, can3_term); +# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_LED + palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_LED, can3_term? HAL_LED_ON : !HAL_LED_ON); +# endif +#endif + } } From 30e3533cefc9165710963fed0f4c03f9cb84323e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 Jan 2025 16:05:18 +1100 Subject: [PATCH 21/85] AP_Periph: support CAN switch and LED defines this allows for hwdef entries like this: PB1 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW PB3 GPIO_CAN1_TERM_LED OUTPUT PUSHPULL SPEED_LOW LOW PB0 GPIO_CAN1_TERM_SWITCH INPUT FLOAT that specifies a termination pin controllable by either a parameter or a hardware switch, with an LED to indicate if termination is active --- Tools/AP_Periph/can.cpp | 36 +++++++++++++++++++++++++++++++++--- 1 file changed, 33 insertions(+), 3 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 4537eb87db9367..5e3690aa6de331 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1616,15 +1616,45 @@ void AP_Periph_FW::can_start() } #endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz + { + /* + support termination parameters, and also a hardware switch + to force termination and an LED to indicate if termination + is active + */ #ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM - palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, g.can_terminate[0]); + bool can1_term = g.can_terminate[0]; +# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH + can1_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_SWITCH); +# endif + palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, can1_term); +# ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM_LED + palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM_LED, can1_term? HAL_LED_ON : !HAL_LED_ON); +# endif #endif + #ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM - palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, g.can_terminate[1]); + bool can2_term = g.can_terminate[1]; +# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH + can2_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_SWITCH); +# endif + palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, can2_term); +# ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM_LED + palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM_LED, can2_term? HAL_LED_ON : !HAL_LED_ON); +# endif #endif + #ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM - palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, g.can_terminate[2]); + bool can3_term = g.can_terminate[2]; +# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH + can3_term |= palReadLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_SWITCH); +# endif + palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, can3_term); +# ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM_LED + palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM_LED, can3_term? HAL_LED_ON : !HAL_LED_ON); +# endif #endif + } for (uint8_t i=0; i Date: Fri, 17 Jan 2025 14:59:47 +1100 Subject: [PATCH 22/85] Tools: define board type for TBS_L431_Periph --- Tools/AP_Bootloader/board_types.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index ee99f778fdd63e..edfb144e21637b 100755 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -390,6 +390,7 @@ AP_HW_TM-SYS-Airspeed 5244 # IDs 5250-5269 reserved for Team Black Sheep AP_HW_TBS_LUCID_H7 5250 AP_HW_TBS_LUCID_PRO 5251 +AP_HW_TBS_L431_PERIPH 5252 #IDs 5301-5399 reserved for Sierra Aerospace AP_HW_Sierra-TrueNavPro-G4 5301 From 70305ba949c137314a6219b5907d691a432bc9cb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Jan 2025 15:02:26 +1100 Subject: [PATCH 23/85] hwdef: added TBS-L431-Airspeed --- .../hwdef/TBS-L431-Airspeed/hwdef-bl.dat | 2 + .../hwdef/TBS-L431-Airspeed/hwdef.dat | 24 ++++++ .../hwdef/TBS-L431/hwdef-bl.inc | 65 ++++++++++++++ .../AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc | 84 +++++++++++++++++++ 4 files changed, 175 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat new file mode 100644 index 00000000000000..04f1494a272ab5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../TBS-L431/hwdef-bl.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat new file mode 100644 index 00000000000000..4f184a84c002d5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat @@ -0,0 +1,24 @@ +include ../TBS-L431/hwdef.inc + +USE_BOOTLOADER_FROM_BOARD TBS-L431-Periph + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# ---------------------- I2C bus ------------------------ +I2C_ORDER I2C1 + +PA9 I2C1_SCL I2C1 +PA10 I2C1_SDA I2C1 + +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 1 + +# ------------------ I2C airspeed ------------------------- +define HAL_PERIPH_ENABLE_AIRSPEED + +# 10" DLVR sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 9 +define AIRSPEED_MAX_SENSORS 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc new file mode 100644 index 00000000000000..b37f849af1ec17 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc @@ -0,0 +1,65 @@ +# hw definition file Matek L431 CAN node + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# use LSE clock source +OSCILLATOR_HZ 32768 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_TBS_L431_PERIPH + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 36 +FLASH_SIZE_KB 256 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# --------------------------------------------- +PA15 LED_BOOTLOADER OUTPUT LOW # blue +define HAL_LED_ON 0 + +# enable CAN support +#PB8 CAN1_RX CAN1 +#PB9 CAN1_TX CAN1 +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +PB1 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW +PB3 GPIO_CAN1_TERM_LED OUTPUT PUSHPULL SPEED_LOW LOW +PB0 GPIO_CAN1_TERM_SWITCH INPUT FLOAT + +CAN_ORDER 1 + +# --------------------------------------------- + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +define HAL_USE_SERIAL FALSE + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 32 +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 +define DMA_RESERVE_SIZE 0 + +MAIN_STACK 0x800 +PROCESS_STACK 0x800 + +# Add CS pins to ensure they are high in bootloader +PA4 MAG_CS CS +PB2 SPARE_CS CS + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc new file mode 100644 index 00000000000000..ae88cbe8423680 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc @@ -0,0 +1,84 @@ +# hw definition file for Matek L431 CAN node + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_TBS_L431_PERIPH + +# use LSE clock source +OSCILLATOR_HZ 32768 + +env AP_PERIPH 1 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# blue LED0 marked as ACT +PA15 LED OUTPUT HIGH +define HAL_LED_ON 0 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 + +# termination control +# the LED is used to indicate to user the termination status +# the SWITCH is an override solder bridge, if high then force termination +PB1 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW +PB3 GPIO_CAN1_TERM_LED OUTPUT PUSHPULL SPEED_LOW LOW +PB0 GPIO_CAN1_TERM_SWITCH INPUT FLOAT + +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 6000 + +# ---------------------- UARTs --------------------------- +# | sr0 | MSP | GPS | +SERIAL_ORDER USART1 + +# USART1 for debug +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +define HAL_RCIN_THREAD_ENABLED 1 From 0cacc900d6c422d65332c1a39bc8f8e15093ab3a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Jan 2025 15:00:09 +1100 Subject: [PATCH 24/85] Tools: added TBS periph bootloader --- Tools/bootloaders/TBS-L431-Periph_bl.bin | Bin 0 -> 17828 bytes Tools/bootloaders/TBS-L431-Periph_bl.hex | 1117 ++++++++++++++++++++++ 2 files changed, 1117 insertions(+) create mode 100755 Tools/bootloaders/TBS-L431-Periph_bl.bin create mode 100644 Tools/bootloaders/TBS-L431-Periph_bl.hex diff --git a/Tools/bootloaders/TBS-L431-Periph_bl.bin b/Tools/bootloaders/TBS-L431-Periph_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..2241cd3331002b12848972c862722ae7024ecd63 GIT binary patch literal 17828 zcmd74dw5e-)<3?_IZ1QUrfo_q^ai9!fzT8TEoc=-(=*b^ua!A^q?`J2)!I}5> z{Qmkr&$rLBv+sMaz4qQ~t-aPdC3<3NX9)j66vUa^=L9fO2?gmA<8`S<>1kTAUH9jbiXJGA<7TGKNq zqh`a6Kdq^h3HjoCWBd*0ubJo*XYvfCZJ@n4**C_?H;q@yH`}K#&MM#LyvAFsXcEGK zsf*Ju$z`H0tD?nut@lRMIuVorF{S^c4JW^fu^t{zTXNa;FFUz2%N0%5hO!F*B0H6o zC6j(q#>r216P!zuf5tFWhxm^e8;JRacW<_qNW@c=i}t;F`B0{o*GSTC$d8!^72tuPE)kP%Uwi%a

z0XHYVcOev5AduXX z0gb@S@CUR4%76KB;PsIQ*706u#;E`!ht-m-z0R*r6M3rgS%4wBHlU|%=GFQ(z9QYt zSq;6PpCvM{WqB5mFmKb};cm8qm{*AIGK#Mz1Y;*7Z&K{-mI}_C>9#~`jos!7b9uIq zAu;n5pQfg0-+ zyNS7F<*wB&ckWt!`tCC;Pp>|6=jqiM_hjC2Lh%@nC>|4H`gf}73eI`cMp)XIB77x~vT^(5l5@8Bc#kh)e$u+pNYJCSW zFcFrdi=Ga5SsGnibbTbpXx0csZW-e$xDQQYm6$H=5slr%yY)VGy4?B7$c?|b=jF=b zqib|RqF@q84w0M27`a@XSplrCX^RZX>0#@zZ81F-fX4NJN^m11JEA|uV}-KYam_<|IFewYd)Xx_cu@G z5R=?Ftusx4JaXa<;X*W!({B4^RD`^aK z!Y%tr?#Jgi*DFezgMDy|l4jZ^IV5%m_Y!wFOZr?{?kSN;3ERxb`Qz&|ii3nBJJ=VC zKofeDJx=Xsbex*-28B3I1$HXLuCr--nL_04aZxNWi&%MCSP9Vi9nNH8oJCA}1b1hm zkS0t+Z})|zUF=+=pUF@1Pl~SS7|sb}()C&MjXsQ)ulH&5lYQvZZO@PR6QXUt4aDNJ z6Y*CQabF;|FOI3tnr1fSC0xY8#dCIXzvLaI`k z$#18p^XRw&E7fd5+=pSQGDKi~NGiE^-oJBZ!)flnFp+WcJ^Dbbp^xjt9QnXtfpkjJ=G_=F{3f@Kf%)Y4PTY4*zSQ$Ah#h?B^#c$flB9y7A>-VuL+|ORXME)pDvGV(HTi@T5 zlh`L(|Avx3W4)8ITN$(l5e~4gMVczYg*+)%1NfjSe)2~$9_ev35fh&m^^m*ma|B#%ZRSrI1k{IP2) z(i`|LHT3N0F=1-pAVxh+;v-yjL^`f~Wn8bEwKF50s>4d3{V?)s=)*BJlrfH0CZ>Ru zIrg_my%7NAc_2Q*j%b7Z%sdxe=e|)zB-VAq!>=xIF=kL86C;;_?(~`d_8ocP^Y2V` zp3DqukvGGHohaDqw0e!gf$#5pK==LDc;)-R19yJ^N3@z!7x;eW1Ea{li(Z)3ey?;; z1bo8<8QYb!OaH4KP}(;+&kENKTVEqNfY%6EjmLzwQe1g!Ja}3|$2YriPY7fk4GC-M zouTypaorx|8Sr>_8S(B!c~K`Mx8-RSW~s%Q;}?G;w@<2=v^d>8X_4hO z+!{*ndnV|859mFaK`DL@D1MLf)zbIPdOMNB7y8VzDeseYVa9}eY8nMyXnDnTjE+B< z5EF&rO2|d`jb>b*vDn(cS{QTsqE+`Y^3pJCX+ z+9xeycxa7R^3=jy%@5q`58O)!%>j@Fq2sGuBY~xng~e zSmK*sQRdqdn%9cJQo^mmmhZ?WW=3LgDysus-lAkL-J(owW8{_#yOnG^u{q>FcqkP* zG#&>YTIzRKGO{bOP}=Fd?gS%W7g>*W9Ex1Jj`)dn6p43KKBbVh4}-?|gF%v<<}DO# z!Y{%b!$~h}QLJ_~bRhCpFfQ5Zt(4>9llE}~3CvC4y0dZTuDTGvk84i1u+8y7hP}Ds zIQSS@rrB;1mPF|{Bfm9%t(%e6aAkSr^{LX4%>9rB=bkW%j2sHHLIQS=ksT`i{l&O( zzwLpt8;C8<%UM{EJ!?W8cB@n;oO@^B2^oC?n7Ce2Qv zB05^bxb1=Fc1AuHCNp)Qs2d-60yoX>A~J{jMnJpInzrv}uF%XK^uK3f<-1314-nhB z;h(*h+SdIoyNOcPGfJAhQRcZ15dT~-nv=k#PbrDPX&nDjJn#=0dHl(<97*2Sh~M4V zsV$1j9^abOob=*n=Xi?=^z=m~CvXC{(AjR2!nPuB*z#7Uwy z(;DKJiEg-~H1&K8a5z8nTG*)Pm=19q&HNJGgSq zVk)O!{}%DmG3-UeREx9c?quaB#`HJnueW3Hc8`R3SS>FRocYC z6K^w+x6WNg+tYq* zMV6F~(khG-9b+QDY9b%Ec$<=IFKj0kzODf&-mHc`_A(fOct`1+R@TenECQF6sk{A#FKCDy-bpF++ zh8{!Nhkjz}KC3h`rbvLUZ_c@)vP1!Lea=>JLC4_zlhn|QszoqCPPO6=%u_8>S+gmc zwy8B!IkP#Mo}unVdPX!oUDX76&S72vtj^;*?GofW$H1|DnImjJ|<^sr>bv-i|3iAZsY!&z`82PjDH%9iX z(*+sbkbj3#fYYzD&jU@+p%-1p$KzzCCRiB18|9V#@9Lj%>PMdcwdn-f&Rc4;dY4*g zj{~4Ky#K0bKV7t6`?!9vatitm7N*g@&p34h?=p!ebo1WhSt@Bh8b1(+Ij#csK>Nm- zD?SeF&4|s}jNDgv2d8#w1RfY>M2pa)a7L4v*~-XGr8B$u{+eMSqJG+$Zv1lILXGIW=tF;Z(_+1bY}7-g(GupZ8m9U%*3LL zVr7&!v&N)$JNQGPyi<>vuYW;$-np}?hZeee^w$dj=ie;Hky zeX@%;ljan`62;iDQDg4f`uA*Sdl}1``d?%-3;%aWPX7qWT0ru3U?}5KNS*^E3x)rg zfaC~p9)g@tPxWNX(ttaC-8fc0ai;$~w&Mb0s;MV=2fXW|`~FN9Jt;bK3^#9%CC?%= z+4=w6Z*6qHDVF(J!5{Z`?-+B%x6!$h1TE%D6YRoYFqeMZCRj0-9XqjY%=W;0IA8BY z=h+;c2e^pVHICVHFBdS2=|SLMd!lb@4^QW?<_-mPK|PlPi0K%s$0(lrf5h*6?EC(a z_3M7z`6n5Rabj&#M?a13v>rQcjP7*WXh!bZ4f{tt>jK#8H5>lF_Bw`PBldc&#|R8B zoO&sSgON-3`bfauslPtnwauC6OHr7Gw>Wr>Agmy+}T9|HDnQ{#c} zLY+nBM(IXrmB1aT6Ruc%#UkFq%JnMt$6Dx*pHX;8?Yza8M{8@NwTpdR?f#Klt}E?r zQ|>T224_0AIj{52E@xeA@HS?X^QsfKEwq5YJd>%0-cSn!ouCQc&JgHNUQ_o8$IO!*h3sW%8Zj7^C%@g7f9AwXtW1-eVd8P5d_Gxh`$W;_F)xfyS(Pk+G?s%Lou>8(ifq8c)Gat~>Q)Gi{i zasaO~${UEqJ9O*gNAPmF6`I6bA8(AN++{RPB>L+vbK`wzfTS~`YJ+^71}94m{h;E# zecCSEEvcb%>I|1P6E9Pgf2o=>q4guQk3-tojvn9+z36F}=y_aia@vI*-n%6-19H5| zT$ArIp*JB#od%p;HS}kUZ9Ea{c~I53BU|_hG|A#1Cj0 zHB>NKBk}X6x`qO?g(9^4K(z{*sD40+;x`#(u1hd{Eg-N98@zV`@*-fhNHn$Eg?!}Z zsV0{Ke68(F!|9+apF6Q~X6vWz%!_m%PN__5VON24>>OJNT>_rMhQ6nrMP6oyRb+Nb zVv}>^bRpKBoB1u)&bGOu+7d$MoKuUFu@*Jt!%7HN(xW9aU&cyKDjLsnh0i*W;Y96+ z5dkZ)Ppp9M9o@M;+!O{>4sSC^t=J*La zAV0_5YoGB5^p2%`9s4KqAV8JZE#a-Ga+cPKl=nQ}thf|4d>$5N6@VJ1%zdBGTCdN#o3J{PEzRr}L{ z)J|Y&IkTN*vE1UkrI_+)0{M#Xv`4k$6t6vK&q2>e zwdFkah?rS%eS=e6FJf;x2{?5R;3O7}z%|f&{{!}t(h3=SO#2%I?2J8C)+8Sp@-VzN zMW`BD&v{UWb*6G7P0NghkF{mp->a+acTK+h)cXAyy16H%=$X3M0=l&zuS=JHE~N?F zQNHk?(=3Gi>5@ro-LTj5*|{WW9q|UWyrS@Sn^Y@g-DMSamMw5;N1ARnF0kF7sk_Zv zf;WimUZ#)a4f^$cv~iv3&ps{JiWnXM7AA* zy@KL1Du>Z~q*SIuN1ZHa>?B7Gl|t8Hsc1ixJ<#Yev@JEC}ff?1JeE z$Oh`G(9Gi`+>AH(GQ4i}$IeZ;>X>qihp~Krhi2r_TQnn0|8Y#Yed{BN1l_9Jo_+-% zOy|)u9w9+E$M5@NFdd_(sirFg#rm{RI_!T$>2ptM*We{|B%-OPfz}vu_v2Itw+DgT zP8`Ng4c_(|p*%a&t%mkQcRU|&7K&3cd#P`BMPB8bk>JQK=VoubCB<^fw9d%TC>P0I zcC^FR&RRKPq?bzb@}q{Jdc_+fp4Fk_M+c53B?URIvj0o{k)c0x&ku0CKFGx5&3fN2 z!W(3LM0@iJ=uJB#%1Gx()w*}QNkO%cw(QI7>9{R>X}D?F5YY_385tga*7;XIv+$FS zWZQ?mOi@pV&idzGSOM;x?Ahi%;bu(l1bD#<-gh1JtK{{g8p?l?q864_b+<~K%y9di zIv-}ndz%|$t{L*11a~(>bt2$Z&bsE>RN0+8#YZfL>zk{J2e)d-K*=PtE9L$hbox_| z>2#-x>uy#o;_t+i`-^1_lX5Rp$l1R2gKv3X2M*VEP8CY(CJQanah*ocpK6hqoL%DK zAqR_dypo;(alEFkMe=JCP=~#}H(G0^wM>o)r*Ubt{x~;LKQCJEr1fmH-Z73-vFwEM zDKWNlQdaHGGQ6X4+T0H43%v^DdZCWY{BE6?%91&zAj1}Hzo8HVm* zMO1TgQ$NSBKIZBgXzMkLdCAnCgEMbLk2)`Cnb(T5EqB^;sD~k)$Ac9%hKW_4n32jc^!w6>^Z7rdzuuJ_!i#NxBFtP-M-kJ`=c7e ze|24|WRY1eRir68U#eJBM`rz^>QT%YYx_4?3W)rK=PdZh?P1MGrs&&6s1JdYdkf2t5zG)-4Nt!PY{ z_llQ)=6?dKTMZscW<7#b9XN|gcts)ZR}|L0MbUsFFC43>TXYb*A7`c*<1xj9XF=sF zBMpMF{YLD=yQ6EGL%NV?D9`zSNZoFKjWd*{mQZaZb)rvp# z+POfLIaA!Nu=d>wXUdA3q+y5MW=?jjO)cqGi0SZazPj$Pl2$-}HTW$)uikrDF-)R)N3_&cP*ca4k0{w_d0Zg{7VOty#1xAq z*hPxNyTA+R9p|CnzEN4)&v2~3`kd3Mf`oz0DH+=n0A=nN)eAE6fddn5P0&3~l)ZX@ z?_`iaIg$V40n*vp_QR0AK{C_*E+7A4NZZI%w621GftTv_`A*oWR6>5*?uvcy43b;Hb$TR0~dd>%MzbYSV(+J(lB6n1y z5R)TI5?LC3NkRD%$_E%OaVg@a&7iBT;x3d>5eSG3*By+XqQ*YoWls z6c^-^sNA{JX7neq zGCh^C9w)@!$w_+Yv*gYJ|2m5-x^iUES=sM*C-{i%fcJR=nSH>!-LM0i&iPRqXz$+P z)cW5U^0*)r z-fM-Iq5WSWy*+Szof$L6`$%5;ndc3!JE!<}JCps1;{OCvh3^A@a_ao7>~S3)@~m-| zCis@O{}AAhe;2?SjR_)rKAep2b?4W;nbOk&$@|)$AyPdNrD^U1?;U4(0LxS$eHdDUJwPSNX!<2>NLsvPFGH|G!?^@tG74Y;kCf-s!n8Pw14nk&oIylH*2fRz8 zdXr&jieqo`E$M%75`R&58uZ0#=qoh@Se;UNJ1C`C@>s)TOkr!sE@w$Yk+-qIC{TUD zhBgyq-$X%zCTcwN=TVcOd4lpAR=A~o72f##tJwng(d$mDSPMNQUi#Yeej{XQcQ|X{UYX*qyMXombZ$3!38o5Hvwu4%otR=dG|&&MRR` z-tR~U)u>VV1&%qKFyQ~9_G&6gm#CptUi5P#-ALsSoS&`_Hr9Z4ez4xyt*OnFvPG`y z$VO)2k@e-`55OONA50ZK+?XsJ8PYS_*$u*W*n8}-@W0fd3ubDb>Cnub9`-27y<1DU zAj8F-h-{2^RS)U8$a=<<*_Wvh@tft0y+5$EGEQJ6rt>7f z)V~PO=HX3V)KxF8mRUlje%xOEn*f;^C)SIvbRd^dT53EUKfrV5sj1lEZ8x`f@Ii*p znmrw|xy@Hv8W&{XbP?GINZHF=D*?ly08_BNBU`Y5+FbCjnx5dw&eVi~9^X9k~tHc_$R3moLQk4eY zJRW*9V&42kE!8KDhgL^Sn;E;OLk)d1u7=(lXNo)>rY6R2{bfz9d2?2Mo{N*Gb2ajH z+#+zf)HOvytvDM{{xC*;wpgrBXMSg6T;cx6;L!SwH)XbVZ0~4x9_}SU0|#8{`R|Qa zSIVCF8-(kHbokvt-W+cP2X6PpU@4A}xmWv{)_r(QvgQQP!s+4lqlO?u4#A3;vl$*Y zy}xtXU;}#+@YRo3*G{TuidcC%`#b0kD`iK#vw!iVtgt6o-p|G}c0lQDQ20HY6eIZ% zT>9rx-O|o6%VuW5e&?Ky$3QbFy*}Vy6Cmby17FlW_FqW~Yh$VkPjc zbY2D?V+X!8ko(3%--Y8^YsAhGGF{jDCvm>FPLK1wW^eUV9p6;JrUL%d;*9HsuaNks z^HG=3>6-EksQXvZryi1E1ktgeaa7ROn{|2ly)!pnA#6v z_7&5XIhPf0frf&@PuG$XUCW~ATGFtVI;>@RbS=~`0IT^G)sH4Xb3%xtjl}b z=R2+yNb_u=SAl7GUjcTgaP&_Daq$aW)ap-1hqvT1?ZQuprkRe&HCuDI*3@?TzR34u zRN{!HwLVyy_T41ZLXSUbw5Wqze!zE!F5U;9fPs@twKGNGuVG~!n_A2u#phph+L-Sc z?DUxM`=*Dk3BH6L-ZH=MErHBD9MH7(!FJPUiEB=9?Q?3I(@w9*;&zfJx0lZM-Xt9F zsLkZ}Y3#b~YUq=Qu4S_8r2#hnGFW3N)SA|~7VWOqOieS_ihXJRV}Jm5y1uJ%n_dmj z*;0Ls<#pigE+3yisdqO{eDyR-m>oQYmnig&1#DO|Y$@4-a$5HocJRi45iOy8ooMO* zNlSWXXx)owc}>8SpWMsus+pD(=7!Gbv_Fn$DB*YTt?#2vUcixW^T9u0W!1E!!5sGa zU=BAk%mlT7VFr4olw_2AsGD?(F+UI8=25)5S(KX5;yK4n&JsxYH3KDFL5Zydr@%t} z45-#l{f6G3QT+1c!Z&>W9$OJ*>6xGOiO_h!{^0oAU-9%|?wYO9@>P3&Q_LyHvI#tCNJOZpDXh-l&S!smT; z+L*`nW^JH)%r63_ye(ep0h%ST%^1_t8!&c$C}nkR5)-O6{hOrlfhY&KxFz16p&mO6 zX$3C^oW}DiYmM_Si#t4&Y-0S>Z-ehXJfw3(qB47P8~i;i@sdU`qHQ1Arg;w!#myu$ zNnWC`UhoWt8Yam-iyiV%gZ@D>o5(*jKzrx2)bDpX=E{}t+q^?RSCZlO4<`YB~fPnL|zy$aMQz$<9|QL<{a=6a2Z|m+q8zu>d-acgp*L@<61vg za=&cJ)U@JO8)^m^=E>5B1{ltEV%39BDVcq1OEdgzE3wu47;Da_^^(%{xgsClQR+sU z$tSMtn^iXpuo?)wUhvkS@OA>;;Xucttxh@)1Ii)?=m=q-t~J><<o$H zsU?y7V(;J!;Z+YF{1w}}uq*PLBSTFrQ&2thTP|{+FHra3!G~L%pG2Wp;M=cfZ3Te( zpr~n$h*VZcd|?c-8`m1&tZ7YXwoNrO+a7#HxwegJL0?g>vB$M;QJi)yeoO2-lzdQm z$DT&KgsHF17Nyv;SBl3@>@17U%RyTSxu%tktbZ;L`OUjSj!7K@C#E~(3m!nlm6ST< zQ4iZX}qM^yk#beb)wl+ckG8#l}A&Sq@0v`Xukc z0~?uWzkdWSYtFGYJuzLxKY@kav4`%$ zgJKMt*;An#y0CE5f%T0}&VO-lOhWvNYG`aM@|(9HT{m5_OA9x(I1PB4u9l7D&^Hf4 z&VJ3OH8FkJ_CjHrMCOM5`b>W6+^OjB+Ey69nkm^*=yz z(34iszj(3}zX{|C{3ep^-w-eL#iP7-wVXsYqBNO2`VI6OjoQWK(AP0+d5u)qh_6p# zT02N_Kaf6q)XGu)hM^*{{Irxa+*hU7=ne5DXT%fAs7b%rDSOr&K`LIN+MamPWIprj zM#W6fJE|igTv$ttq|Z2Ek4mbzRZ1NuHEF&eBxlUtBwYjfdF_`~`if6hS?*|}^UKdG z#`d_1y;a6;ZABzN?N+cc$HoIpDhnC}GDyEYAm&>naI1OEgbRu#+(=ak1FueepFqD+ zNEtdFl|?6N^vwGmjS5MHZwl^4i=#x}`eQG&&dC(f+QQwpUgB!Aq+QZBXXN+_i4&co zQM~2f>v}J(<2(5Y3sk~yIGfg|u_gL!T``N>rds$Z!*fwBY^+j4e^H5LFaRBML8`by z9Dy%kj>Z z^Da<%_e+&P7NPn43oq2_z=PD#Y4t*Y_Pc)p;WhA4`$XC*wZa!6=2zn`qjh|Ru`^rh zg=#A{pZUH|MK$z0m4T#4_2#1?S9I>8PTdmSVtx^0Au}xQl_HV*Bdo>Zrn*_!d%fb- z@Xy0HJkc>b*SrB;+e#w8jGKN-gpGcWG9HD6wj;6;oR78e;C(#w2946*U=v%Sq~)`< zC5kKGiC;&)zPv=q%|9%aDCzmEnNtk;1iuOS8k8IJ_ky0#v-KU$Kx|IPKPuJgsi9lF zgs>H#NIR>NO={>rytF>1?^Q!XsDplQVvl&#FULN__6L3v($n}h#?X74v{6hDmxwvg z-tLk%X12t34PTmMNt3duzfJt?B5!<-8l22KQyph3C&u zAbzgqG_}+)So8LS&|%}fl~$1`oUY=6My6Pd&&#M?FJdG!BQ6rtt6oS?!w$}l#LptK zIYPe)iWA~aJd|z4`1z4p!UAD15PvxxQ;Ci#9faOKx;~|odIZ4dHwfQy z^XI`TZ>O3HVCAsaUwcq;W#(sCz4^jkcq-EOZL4aA2OGC2*5={pSc`x!Pv81{|dYrJ2RG8YInll#z(*Lk?6T?k>Xt~B7G0ib4_omMPRXK#>%qAm20n3s8D>!CWa&y_lB~>m)F0CQVPp4=)tLUzaKg?BL5C_F=fN4bKE>?L5}VJ zs#;>}^%41(;kw#A0~&pK>3SjYIE&pm5+>$YU*3NsJQ=|K%hZt7J1Nub8VpPt(Cdr5 z24lNZHUkD<2_KT5n5hxFVPK@a`2u(tg8Ilh$3O3x^T9{TV( zo}qV!)>FR+su!m82^hpnj1c;L0b8D0`w2IClAdvRfI9e2eMMINT6oIKs;*)M^dMeu zTzQMg1~(M6h?$ak*i#J)L3cg9UubV(?kwdy6VRs_eg3BE(FZme=ZY%4^WfE;8S4{` zk^f2Gb=DRyY&G^CmO=-(hKWdH4|40Q7!}_OK;Jz=YFG*1H25|4M%eQhYHNzxRo7Xm zMQ%D;wZLNZoSIZIWX`N&VJ!d*{XJ|n9`+Qhz`1%%#psBSsYJf+0&MfJK-04TKN+kW z7CWqk`l&klVWp9E96Voq_6o<~`hrX`=0*BQ`keA7oQBi3a>wAK^HM-bxv5!Fxzz0B z{diy5`FXnhw9~AV0FU~hPYtaAOgE@GH}LZ+Wro_%^-TV=@JWaRymzSZD#-s9Yw-u( zRnk0K;YP^!rHW=DESJ}mh|~wCu$J113ae1Rm6d2cIJPeVFuewtsQD4)XXNIY{-lKMbWjvbzhmil(DOyvA;U z#~$tj^%05D>{#x#aq4AK)ZKly2snS??IPGRzED$^q?E&A++Xb86Jh`ReSS|wW5^!R z8lH`49KaZNYw@!Yc2f3$#!xaqNXkGG;|vnEI32%4uP^Q=ZhF4|8d~<{A6k!^jGe42 z4qotEp-nb+yRu2gGQ~vb7pHw4!@$K-D{-V$*gH=sTOGL?{Ye@hL7=f~n7C*U>`W# zu&j2jqWt_zW-2$(GFnG{!V9|CpvTFMXbO%iJ4{ij!ut^2JL=2L9zhw#0ld_H6i``M zr+S7Q*l*f~!a?amd_}^dgz~M5Bj*B`{M;T!%})dnx~qj(j#*Fv5vKT(%n;;RN+ zQTmu$F=Nr0Iw$lc#@EkOpQ$r1F(XY=XYQhlp6C^exp*Oj;gmP8lY6roKz+8|Ej zQHwYiffP|rNaUO8eWPcLA-M?Fr6eBm1d+92HFS3*CVw#Cl@zbZQF}PU!XCbwO2sXA z8p>N&H%INv&ES`wl1g(+HE>#RrkeWpuc$dAu7J!38cp{lHjhcuhn7yhGo|)~l;Aks z@qS6GE~QF$>Y_w*%Y?Xtf;U%j)gw@#FGq_?`a z4w6DNPG6N#lfEhwVdtt{H9J?eAoQ*}UDLbj3_|){8MkNLm3e#SU5m;qA@iq*nfH`I z)@Ru0_rE6kT7bk%zX3K;+rQ@~x>hrd?`&C(Z{XJnRUt{OSw;U z6vW$fqo)8JB#B9~fsOca>y0VHj&;+#mBXHSxciXcx0oGESPMo(chK*^cu7#ZbfP)c7aw00XadTMfcCgq1R<$sydB$QA{ z5*MeGA5k{oEkn;5^+1UiNkUe+$}kEQOZ^yatr~bFX5whfBlBFc`_rH#75f z<$UL|S`HjzS(T+-i!YuN+Lyvc8apZVUGP_SG~vEqY{yQtYeqZYkL_;%w|1I~1GAo$tqX*Zf;MyI ze#l`)+u4qPLEn7$CcM65^rIpTQ4 zpCF!s`0t3Vh)>`fSKgt^$wvBPj6=u0Y8*FAQA3fa7Xk8+{fR|eo*^)WM%&?YB!zxQ zu0+oc-Twqg>gnL!dh};2;%N?^8)=8qQy>L(YL}$qOAA`cn&_9;MtJQ~4>sC1){;9! zys@^-Rjg|(m4Hp!KCT{~@s)dFbxzMRb~E(w>KPaOJcH^ro1OU1>@>bi z?$g$HJ2gQ@GvYT4XtaNW^*3sJZn#Wgwm`S=om@KN3t(1Gz^FESMPws+7qEiWYwny| zwdVHw+_iVD{^i`|&Si6!%rBfbXX(l{wQdP8I-dI~c)PSMjuh|xdT?d!b{)!`Rkxc; zif>qaM^(*AQ|&#sudJU-JSe~9hvvu=>G)qGCh!J?Q%HY-@LeY1|A4p?;YEaYgjW#s zDDOf%W<4*{dsp)?LDOS_PbVM{F$2QG=zv;G%=pXkmD%J M2Hq!X{;x&<2k|0!rvLx| literal 0 HcmV?d00001 diff --git a/Tools/bootloaders/TBS-L431-Periph_bl.hex b/Tools/bootloaders/TBS-L431-Periph_bl.hex new file mode 100644 index 00000000000000..f9c8d2409a7e9a --- /dev/null +++ b/Tools/bootloaders/TBS-L431-Periph_bl.hex @@ -0,0 +1,1117 @@ +:020000040800F2 +:1000000000090020B1010008952300084D230008D5 +:10001000752300084D2300086D230008B301000874 +:10002000B3010008B3010008B3010008313400082F +:10003000B3010008B3010008B3010008B3010008D0 +:10004000B3010008B3010008B3010008B3010008C0 +:10005000B3010008B301000889410008B14100085C +:10006000D94100080142000829420008B3010008F4 +:10007000B3010008B3010008B3010008B301000890 +:10008000B3010008B3010008B30100080123000810 +:100090002D2300083D230008B30100085142000849 +:1000A000B3010008B3010008B3010008B301000860 +:1000B00025430008B3010008B3010008B30100089C +:1000C000B3010008B3010008B3010008B301000840 +:1000D000B3010008B3010008B3010008B301000830 +:1000E000B5420008B3010008B3010008B3010008DD +:1000F000B3010008B3010008B3010008B301000810 +:10010000B3010008B3010008B3010008B3010008FF +:10011000B3010008B3010008B3010008B3010008EF +:10012000B3010008B3010008B3010008B3010008DF +:10013000B3010008B3010008B3010008B3010008CF +:10014000B3010008B3010008B3010008B3010008BF +:10015000B3010008B3010008B3010008B3010008AF +:10016000B3010008B3010008B3010008B30100089F +:10017000B3010008B3010008B3010008B30100088F +:10018000B3010008B3010008B3010008B30100087F +:10019000B3010008B3010008B3010008B30100086F +:1001A000010F000800000000000000000000000037 +:1001B00002E000F000F8FEE772B6374880F30888E6 +:1001C000364880F3098836483649086040F2000016 +:1001D000CCF200004EF63471CEF200010860BFF39D +:1001E0004F8FBFF36F8F40F20000C0F2F0004EF669 +:1001F0008851CEF200010860BFF34F8FBFF36F8FBD +:100200004FF00000E1EE100A4EF63C71CEF2000114 +:100210000860062080F31488BFF36F8F03F0D0FDD1 +:1002200003F052FE4FF055301F491B4A91423CBF2C +:1002300041F8040BFAE71D49184A91423CBF41F8C6 +:10024000040BFAE71A491B4A1B4B9A423EBF51F86E +:10025000040B42F8040BF8E700201849184A9142B1 +:100260003CBF41F8040BFAE703F0AEFD03F07EFE5D +:10027000144C154DAC4203DA54F8041B8847F9E7D7 +:1002800000F042F8114C124DAC4203DA54F8041B52 +:100290008847F9E703F096BD00090020001100200F +:1002A0000000000808ED00E0000100200009002027 +:1002B00028450008001100207C110020801100203A +:1002C000043B0020A0010008A4010008A4010008CC +:1002D000A40100082DE9F04F2DED108AC1F80CD0D3 +:1002E000C3689D46BDEC108ABDE8F08F002383F300 +:1002F00011882846A047002003F00AFAFEE703F021 +:1003000093F900DFFEE70000F8B500F00BFE03F004 +:10031000F9FC074603F04AFD0646C0BB274B9F4247 +:1003200035D001339F4235D0254B27F0FF029A424A +:1003300033D1F8B200F03AFC354642F2107400F0C6 +:100340003BFC08B10024254601F0E2F848B3032045 +:1003500000F03AF80024254636B11A4B9F4203D0EC +:1003600003F01CFD00242546002003F0D5FC0DB150 +:1003700000F040F800F054FC02F014F80546ACB967 +:1003800000F096FC4FF47A7003F0C8F9F7E73546B1 +:100390000024D4E704460125D1E705464FF47A74DA +:1003A000CDE7B4F57A7F08BF0125D5E701F0FAFF64 +:1003B000431BA342E4D900F01DF8DDE7010007B0BC +:1003C000000008B0263A09B0084B187003280CD872 +:1003D000DFE800F008050208022000F001BE02205C +:1003E00000F0F4BD024B00225A60704780110020DB +:1003F0008411002010B501F08BF830B1234B03229B +:100400001A70234B00225A6010BD224B224A1C4610 +:1004100019680131F8D004339342F9D16268A242DD +:10042000F2D31E4B9B6803F1006303F520439A420D +:10043000EAD203F085FC03F097FC002000F08CFD6D +:100440000220FFF7C1FF164B9A6D00229A65996F43 +:100450009A67996FD96DDA65D96FDA67D96F196EB6 +:100460001A66D3F88010C3F88020D3F8803072B6B3 +:100470004FF0E0233021C3F8084DD4E9003281F376 +:1004800011889D4683F308881047BDE7801100203E +:100490008411002000A0000820A000080011002006 +:1004A00000100240094A136849F2690099B21B0C16 +:1004B00000FB01331360064B186844F2506182B2AE +:1004C000000C01FB0200186080B27047141100207C +:1004D0001011002010B500211022044600F09AFDF2 +:1004E000034B03CB206061601868A06010BD00BFA3 +:1004F0009075FF1FF0B5ADF5517D6EAC4FF4C47231 +:1005000007460D462046002100F084FD01F04AFF19 +:10051000264B4FF47A72B0FBF2F0186093E80700B4 +:10052000022384E807000DF5ED702382FFF7D2FF68 +:1005300042F204631E49238407A803F08FFF1D23A2 +:1005400084F832310DF2EB2207AB0DF1340C1E466C +:1005500003CE664510605160334602F10802F6D1C1 +:1005600030681060337913710FAE31460122204696 +:1005700000F09CFD00230393AB7E029305F1190369 +:10058000019380B20123CDE904600093E97E05A3C5 +:10059000D3E90023384602F01BFB0DF5517DF0BD79 +:1005A000AFF300809E6AC421818A46EE8C11002040 +:1005B0006C4400082DE9F0412C4C237ADAB08046D7 +:1005C0000D465BBB27A9284600F096FE074600288B +:1005D00042D19DF89D60C82E3ED801464FF4A662D8 +:1005E000204600F017FD4FF48073C4F8F8314FF443 +:1005F0000073C4F80C334FF44073C4F8203432460F +:100600000DF19E0104F1090000F0F2FC26449DF872 +:100610009C30777223720BB9EB7E2372812200210A +:1006200006AC27A800F0F6FC0122214627A800F01E +:10063000A9FE00230393AB7E029305F1190380B258 +:1006400001932823CDE904400093E97E05A3D3E973 +:100650000023404602F0BCFA5AB0BDE8F08100BF6A +:10066000AFF3008026417272DF25D7B7D421002076 +:10067000F0B5254E4FF48A7505FB0065F1B096F88C +:10068000D83085F8DC300024D822214685F8E840AF +:100690003AA800F0BFFC06F1090000F0B3FCD5F861 +:1006A000E4308DF8F000C2B206AF06F109010DF199 +:1006B000F100CDE93A3400F09BFC394601223AA81A +:1006C00000F096FE80B2CDE9047008230127CDE941 +:1006D000023706F1D803019330230093317A0B4897 +:1006E00007A3D3E9002302F073FAA04206DD01F06C +:1006F00059FEC5F8E000384671B0F0BD2046FBE772 +:1007000078F6339F93CACD8DD4210020A4210020F8 +:100710002DE9F0411D4D1E4E1E4F86B0284602F0B9 +:1007200083FA034658B30024CDE90344ADF81440DE +:10073000027B8DF8142099684068029403AA03C2D2 +:100740001B68DFF8548043F00043029301F02CFE55 +:10075000821941F10003009402A9384601F0C0F863 +:10076000A04205DD284602F063FA88F80040D5E78C +:1007700098F80030072B05D8013388F8003006B010 +:10078000BDE8F081014802F053FAF8E7A421002007 +:1007900040420F00102700200927002070B50D46A9 +:1007A00014461E4602F070F950B9022E10D1012CE9 +:1007B0000ED112A3D3E90023C5E90023012007E0ED +:1007C000282C10D005D8012C09D0052C0FD00020E2 +:1007D00070BD302CFBD10BA3D3E90023ECE70BA3B6 +:1007E000D3E90023E8E70BA3D3E90023E4E70BA355 +:1007F000D3E90023E0E700BFAFF30080401DA12054 +:1008000026812A0B78F6339F93CACD8D9E6AC42128 +:10081000818A46EE26417272DF25D7B7F017304A3B +:1008200039059E5638B505460E4C0021013500F0BD +:10083000B5FBA4F82C55B4F82C0500F097FB78B163 +:10084000B4F82C0500F0A2FB014648B9B4F82C0519 +:1008500000F0A4FBB4F82C350133A4F82C35EAE7FA +:1008600038BD00BFD421002010B50A4B0A4A1A60D7 +:1008700003F5805393F870203AB9DC6E2CB1204612 +:1008800000F0C4FE204601F001F8BDE81040034826 +:1008900000F0BCBE10270020C844000868370020C4 +:1008A0002DE9F04F8FB000AF05460C4602F0ECF892 +:1008B00000284BD1237E022B1BD1E38A012B18D1B8 +:1008C00001F070FD0646FFF7EDFD03464FF4C870DA +:1008D000DFF8D482B3FBF0F206F5167602FB103394 +:1008E00016FA83F3C8F80030E37E33B9A74B002231 +:1008F0001A703C37BD46BDE8F08F07F12401204651 +:1009000000F0AEFC0028F4D107F11400FFF7E2FD7F +:1009100097F8264007F11401224607F1270003F05B +:100920006BFD0028E2D10F2C08D8984B1C70D8F82A +:100930000030A3F51673C8F80030DAE797F82410F2 +:100940000029D6D0284602F097F8D2E7E38A282B70 +:1009500033D010D8012B2BD0052BCAD1BFF34F8F2A +:100960008B498C4BCA6802F4E0621343CB60BFF33F +:100970004F8F00BFFDE7302BBBD1874EE17E327A2F +:100980009142B6D1607E3146002291F8DC5085421A +:1009900000F0AD800132042A01F58A71F5D1326888 +:1009A00040F6B831FA328A4294BF32603160A0E733 +:1009B00021462846FFF79EFD9BE721462846FFF784 +:1009C000F9FD96E7B2F8EC507B6005F103094FEAB8 +:1009D00099094FEA8902D11DC908A8EBC1039D46B8 +:1009E000EB460021584600F015FB04F1EE012A46C3 +:1009F0003144584600F0FCFA7B6813B9012000F03E +:100A0000ABFA96F8D20000F0B1FA044630B9307271 +:100A100000F0CCFA204600F09FFAB0E0D6F8D420DF +:100A20003AB996F8D200B6F82C25824201D8FFF7E1 +:100A3000F9FED6F8D4202A44944208D296F8D2007F +:100A4000B6F82C250130824201D8FFF7EBFE706822 +:100A50005FFA89F2594600F0E5FA08B9C54679E02F +:100A6000726896F8D2002A447260D6F8D42005EB5A +:100A70000209C6F8D49000F079FA814509D396F8B6 +:100A8000D220D6F8D4000132001B86F8D220C6F856 +:100A9000D400FF2D0FD80024347200F087FA2046CE +:100AA00000F05AFA00F034FD3C4B188108B9FFF70A +:100AB000A1FCC5461DE7BB6896F8D9000AFB036296 +:100AC000FB68D2F8E41082F8E83001F58061C2F8E2 +:100AD000E030C2F8E410FFF7CBFDFFF719FE96F8FF +:100AE000D920013202F0030286F8D920B6E74FF48C +:100AF0008A7A0AFB02F505F1EA013144204600F04A +:100B0000ABFCF86000287FF4F4AE3544012285F890 +:100B1000E82001F047FCD5F8E020D6ED007ADFEDC3 +:100B2000206A801A192838BF192040F6B83290423E +:100B300028BF1046B8EE677A07EE900AF8EEE77A1B +:100B400067EEA67ADFED176AE7EE267AFCEEE77A23 +:100B5000C6ED007A96F8D9307168BB600AFB03F4E1 +:100B6000321992F8E8505DB1D2F8E4308B42E84691 +:100B70003FF428AF002182F8E810C2F8E010C54623 +:100B80007368064A9B0A01331381B2E69D21002057 +:100B900000ED00E00400FA05D42100208C110020B3 +:100BA000CDCCCC3D6666663FA0210020014B18707D +:100BB000704700BF9811002038B54FF00054144B17 +:100BC00022689A4221D1607DF0B1124B124918700F +:100BD0001248237D03724FF48073C0F8F8314FF44C +:100BE0000073C0F80C3300254FF44073C0F8203474 +:100BF000C0F8E450C922093000F0FAF9E022294691 +:100C0000204600F007FA012038BD0020FCE700BFB5 +:100C10009AAD44C59811002016000020D421002070 +:100C200037B500F075FC194D1949288102230122BE +:100C300018486B7101F050FA00230193164B1749C5 +:100C400000931748174B4FF4805201F0EDFE164BFE +:100C5000197811B1124801F00FFF01F0A3FB04460F +:100C6000FFF720FC4FF4C873B0FBF3F202FB130351 +:100C700004F5167010FA83F00C4B186003F096F828 +:100C800008B10F232B8103B030BD00BF8C110020B1 +:100C900040420F00102700209D0700089C110020F3 +:100CA000A4210020A108000898110020A021002004 +:100CB0002DE9F04F2DED028B0FF23829D9E900898B +:100CC000834C93B00BAE9FED7E8BFFF721FD814FE0 +:100CD000DFF828A200230A93ADF834300B93736039 +:100CE0004FF0000B5B468DED008B01250DF11D02D1 +:100CF00007A938468DF81C508DF81DB001F09AF9FF +:100D00009DF81C30002B40F0A580204601F0BCFE71 +:100D10000646002845D1704F01F044FB3B689842DD +:100D20003FD301F03FFB8246FFF7BCFB4FF4C87393 +:100D3000B0FBF3F202FB13030AF5167010FA83F00E +:100D40003860664F97F800B0CBF1100ABBF1000F86 +:100D500014BF33462B465FFA8AFA0EA88DF8283066 +:100D6000FFF7B8FBBAF1060F28BF4FF0060A0EAB2B +:100D700003EB0B0152460DF1290000F039F90AABE3 +:100D80000393182302930AF10102554BD2B2CDE925 +:100D90000053049220464CA3D3E9002301F0BAFE8D +:100DA0003E7001F0FFFA4F4A4F4D1368C31AB3F576 +:100DB0007A7F2ED3106001F0F7FA02460B462046E8 +:100DC00001F040FF204601F05FFE10B32B7A474E42 +:100DD000002B14BF03230223737101F0E3FA0EAF5B +:100DE0004FF47A730122B0FBF3F03946306030469D +:100DF00000F00EFA182302933D4B019380B240F2AB +:100E00005513CDE90370009342464B46204601F04E +:100E100081FE2B7A93B101F0C5FA002607464FF404 +:100E20008A7A95F8D900304400F003000AFB005399 +:100E300093F8E82092B30136042EF2D1C82002F0D4 +:100E40006DFC2B7A002B7FF43DAF13B0BDEC028B11 +:100E5000BDE8F08FDAF8143083F00803CAF81430D4 +:100E6000594610220EA800F0D5F80DF11E0308AA6D +:100E70000AA9384600F03AFE96E803000FAB83E873 +:100E800003009DF834308DF844300A9B0E930EA970 +:100E9000DDE90823204602F0A9F821E7D3F8E02095 +:100EA00042B12B68FA2B38BFFA23BA1A0533B2EBDA +:100EB000430FC0D3FFF7DCFB0028BCD1BEE700BF67 +:100EC0000000000000000000401DA12026812A0B28 +:100ED000A421002010270020A02100209D21002017 +:100EE0009C21002004270020D42100208C11002008 +:100EF00008270020F1C6A7C1D068080F00040048E9 +:100F000008B5054800F090FEBDE80840034A0449D2 +:100F1000002003F04DBA00BF102700203038002019 +:100F20006908000870B502F095FD094E094D308042 +:100F3000002428683388834208D902F087FD2B6893 +:100F400004440133B4F5204F2B60F2D370BD00BFD1 +:100F500024380020F837002002F02EBE00F1006097 +:100F6000920000F5204002F0B1BD0000054B1A6868 +:100F7000054B1B889B1A834202D9104402F066BDC0 +:100F800000207047F837002024380020024B1B68EF +:100F9000184402F061BD00BFF8370020024B1B6807 +:100FA000184402F06BBD00BFF8370020064991F8E5 +:100FB000243033B10023086A81F824300822FFF777 +:100FC000CDBF0120704700BFFC370020022802BFC0 +:100FD000024B4FF400229A61704700BF00040048A2 +:100FE000022802BF014B08229A61704700040048A2 +:100FF00010B50023934203D0CC5CC4540133F9E70D +:1010000010BD000003460246D01A12F9011B002948 +:10101000FAD1704702440346934202D003F8011B01 +:10102000FAE770472DE9F8431F4D144695F8242040 +:101030000746884652BBDFF870909CB395F8243081 +:101040002BB92022FF2148462F62FFF7E3FF95F8D6 +:101050002400C0F10802A24228BF2246D6B241466F +:10106000920005EB8000FFF7C3FF95F82430A41B26 +:101070001E44F6B2082E17449044E4B285F824606A +:10108000DBD1FFF793FF0028D7D108E02B6A03EBF1 +:1010900082038342CFD0FFF789FF0028CBD1002005 +:1010A000BDE8F8830120FBE7FC3700202DE9F3477A +:1010B0000D46044600219046284640F27912FFF77B +:1010C000A9FF234620220021284601F031FF231DDD +:1010D00002222021284601F02BFF631D032222213A +:1010E000284601F025FFA31D03222521284601F0F3 +:1010F0001FFF04F1080310222821284601F018FFE1 +:1011000004F1100308223821284601F011FF04F1F0 +:10111000110308224021284601F00AFF04F11203BE +:1011200008224821284601F003FF04F1140320227D +:101130005021284601F0FCFE04F1180340227021E2 +:10114000284601F0F5FE04F120030822B0212846CC +:1011500001F0EEFE04F121030822B821284601F037 +:10116000E7FE04F12207C0263B4631460822284606 +:10117000083601F0DDFEB6F5A07F07F10107F3D1D7 +:1011800094F832308DF8073031460DF1070308220C +:10119000284601F0CDFE002604F1330A9DF8073001 +:1011A0004FEAC6099E4209F5A47720D394F832315C +:1011B000502B28BF50238DF80730B8F1000F08D10D +:1011C00039460DF107030722284601F0B1FE09F266 +:1011D0004F17002604F233149DF807309E4207EBA8 +:1011E000C6010DD30731C80802B0BDE8F0870AEB8D +:1011F000060308223946284601F09AFE0136CDE75B +:10120000A3190822284601F093FE0136E4E7000006 +:1012100013B504460846002101602346C0F80310B8 +:101220002022019001F084FE0198231D022220213A +:1012300001F07EFE0198631D0322222101F078FE59 +:101240000198A31D0322252101F072FE019804F1EB +:1012500008031022282101F06BFE072002B010BD08 +:10126000F7B5047F05460E462CB1838A122B02D9AE +:10127000012003B0F0BD002319460722009628463E +:1012800001F01AFD731C0093012200230721284658 +:1012900001F012FDD4B9B31C0093052223460821A6 +:1012A000284601F009FD0D24B378102BE0D837460D +:1012B000B278BB1B934210D32B7FA88A0734E40873 +:1012C000B3B9844294BF00200120D2E7AB8ADB008F +:1012D000083BDB08B3700824E6E7FB1C00932146BB +:1012E00000230822284601F0E7FC08340137DFE735 +:1012F000201A18BF0120BCE7F7B5047F05460E464B +:101300002CB1838ACA2B02D9012003B0F0BD00237F +:10131000194600960822284601F0CEFC731CD4B969 +:101320000822009311462346284601F0C5FC1024EC +:101330007378C82BE8D8012372785F1C013B934275 +:1013400010D32B7FA88A0734E408B3B9844294BF32 +:1013500000200120D9E7AB8ADB00083BDB08737073 +:101360000824E5E7F31900932146002308222846C4 +:1013700001F0A2FC08343B46DEE7201A18BF01202A +:10138000C3E70000F7B50D4604460021164628467F +:101390008122FFF73FFE234608220021284601F064 +:1013A000C7FD94F901206378002AB8BF7F238DF828 +:1013B00007309EB90DF1070307220821284601F0E6 +:1013C000B7FD0F27002602349DF807309E4207EB39 +:1013D000C60105D30731C80803B0F0BD0827F1E7FF +:1013E000A3190822284601F0A3FD0136ECE700000E +:1013F000F7B50E460546002114463046CE22FFF7CB +:1014000009FE2B4628220021304601F091FD2B7A5F +:10141000C82B28BFC8238DF807308CB90DF10703FE +:1014200008222821304601F083FD30242F469DF804 +:1014300007207B1B934205D3E01DC00803B0F0BD1D +:101440002824F3E707F1090321460822304601F07A +:101450006FFD08340137EAE7F7B5047F05460E460D +:1014600034B1838AB3F5827F02D9012003B0F0BD85 +:101470000096012310220021284601F01DFCDCB952 +:10148000B31C0093092223461021284601F014FCC6 +:1014900019247388B3F5807FE7D837467288BB1B61 +:1014A000934210D32B7FA88A0734E408B3B984424F +:1014B00094BF00200120D9E7AB8ADB00103BDB089A +:1014C00073801024E5E73B1D00932146002308228A +:1014D000284601F0F1FB08340137DFE7201A18BF76 +:1014E0000120C3E730B5094D0A4491420DD011F8EF +:1014F000013B5840082340F30004013B2C4013F00B +:10150000FF0384EA5000F6D1EFE730BD2083B8ED49 +:10151000F7B5384A106851686B4603C36A463649C6 +:101520003648082302F078FF0446002833D10A2504 +:10153000334A106851686B4603C36A4631492F48E5 +:10154000082302F069FF0446002849D00369B3F577 +:10155000583F45D8B0F8661040F2264291423FD13C +:10156000294A024402F15C018B4239D35C3B234996 +:1015700000209E1AFFF7B6FF3246074604F16401C9 +:101580000020FFF7AFFFA3689F4229D1E36898428C +:1015900008BF002524E00369B3F5583F27D8418BE5 +:1015A00040F22642914220D1174A024402F1100132 +:1015B0008B4218D3103B114900209D1AFFF792FF70 +:1015C0002A46064604F118010020FFF78BFFA368A6 +:1015D0009E4202D1E368984201D00D25A8E700257C +:1015E000284603B0F0BD1025A2E70C25A0E70B2587 +:1015F0009EE700BF8C440008DC5F030000A00008E9 +:1016000095440008905F03000860FFF710B5037C65 +:10161000044613B9006802F0E7FE204610BD000042 +:101620000023BFF35B8FC360BFF35B8FBFF35B8FA0 +:101630008360BFF35B8F7047BFF35B8F0068BFF3BE +:101640005B8F704770B505460C30FFF7F5FF05F16D +:10165000080604463046FFF7EFFFA04206D93046A1 +:101660006D68FFF7E9FF2544281A70BD3046FFF783 +:10167000E3FF201AF9E7000070B50546406898B10D +:1016800005F10800FFF7D8FF05F10C0604463046C7 +:10169000FFF7D2FF8442304694BF6D680025FFF704 +:1016A000CBFF013C2C44201A70BD000038B50C461D +:1016B0000546FFF7C7FFA04210D305F10800FFF76A +:1016C000BBFF04446868B4FBF0F100FB1144BFF3B6 +:1016D0005B8F0120AC60BFF35B8F38BD0020FCE75F +:1016E0002DE9F041144607460D46FFF7C5FF844239 +:1016F00028BF0446D4B1B84658F80C6B4046FFF7F3 +:101700009BFF3044286040467E68FFF795FF331A00 +:101710009C4203D86C600120BDE8F0816B60A41B83 +:101720003B68AB602044E8600220F5E72046F3E721 +:1017300038B50C460546FFF79FFFA04210D305F1D0 +:101740000C00FFF779FF04446868B4FBF0F100FB7C +:101750001144BFF35B8F0120EC60BFF35B8F38BD9A +:101760000020FCE72DE9FF41884669460746FFF760 +:10177000B7FF6C4606B204EBC6060025B44209D09A +:101780006268206808EB0501FFF732FC63680834E3 +:101790001D44F3E729463846FFF7CAFF284604B040 +:1017A000BDE8F081F8B505460C300F46FFF744FF61 +:1017B00005F1080604463046FFF73EFFA0423046DA +:1017C00088BF6C68FFF738FF201A386020B13046B8 +:1017D0002C68FFF731FF2044F8BD000073B51446B4 +:1017E00006460D46FFF72EFF844228BF04460190AF +:1017F000DCB101A93046FFF7D5FF019B33B9326850 +:10180000C5E90233C5E9002401200CE09C4238BF41 +:1018100001942860019868608442F5D93368AB6010 +:10182000241AEC60022002B070BD2046FBE70000E5 +:101830002DE9FF410F466946FFF7D0FF6C4600B225 +:1018400004EBC0050026AC4209D0D4F8048054F85B +:10185000081BB8194246FFF7CBFB4644F3E7304676 +:1018600004B0BDE8F081000038B50546FFF7E0FFA1 +:10187000044601462846FFF719FF204638BD000000 +:101880000121884238BF084602F098BD08B102F035 +:10189000ABBD704710B4026854681A4623465DF821 +:1018A000044B184700207047002070477047000025 +:1018B000002070470E20704700F5805090F8D80047 +:1018C000C0F340007047000000F5805090F9E00040 +:1018D0007047000000F58050C0F8DC100120704710 +:1018E000F7B50C68BDF8207014F0005473D10D7B6F +:1018F000082D70D8302585F31188456AAE687601C9 +:101900000CD4AC68240108D4AC6814F0805460D1C5 +:1019100084F31188204603B0F0BD01240E6804F161 +:10192000180C002EB8BFF6004FEA0C1CB4BF46F0EE +:101930000406760545F80C600E680FFA84FC16F074 +:10194000804F18BF05EB0C1E05EB0C1C1EBFDEF80C +:10195000806146F00206CEF880610E7BCCF884618F +:1019600005EB04158E68C5F88C614E68C5F8886172 +:10197000DCF8805145F00105CCF8805141F2780542 +:1019800000EB441C660105EB4414AC440444CCE970 +:1019900000230D46083401F10C0C55F804EB44F813 +:1019A00004EB6545F9D12D882580841904F5805410 +:1019B00007F0030594F8946026F00B06354384F88D +:1019C0009450002484F31188009700F035FD012025 +:1019D000A1E70224A2E74FF0FF309CE713B500F522 +:1019E00080540191E06EFFF747FE1F280AD9019944 +:1019F000E06E2022FFF7B6FEA0F1200358425841C6 +:101A000002B010BD0020FBE708B5302383F3118836 +:101A100000F58050C06EFFF703FE002383F31188AA +:101A200008BD00000022026082814260826070472F +:101A300010B500220023C0E90023002304460381DF +:101A40000C30FFF7EFFF204610BD0000F0B5054653 +:101A500000F580500C4690F8D83013F0040FC3F313 +:101A6000800108BF114661F3820380F8D83005EB8E +:101A7000441303F58453103389B01B79D8074FEA18 +:101A800044162FD582B319072ED46846FFF7D0FF2E +:101A900005EB441303F5845303AA03F10807186800 +:101AA0005968144603C40833BB422246F7D118686C +:101AB00020609B88A380DDE90E23CDE9002301236C +:101AC000ADF808302B6869461B6C284698473544AA +:101AD00005F5845510352B791A075CBF43F00803D0 +:101AE0002B7101E0002AF2D109B0F0BD2DE9F047D9 +:101AF0009A4688B0074688469146302383F311887A +:101B000007F580546846FFF793FFE06EFFF79AFDF4 +:101B10001F282AD9E06E20226946FFF7A5FE20285B +:101B200023D103AD444605AB2E4603CE9E42206032 +:101B30006160354604F10804F6D130682060B3884E +:101B4000A380DDE90023C9E90023BDF80830AAF825 +:101B50000030002383F3118853464A4641463846F5 +:101B600008B0BDE8F04700F02BBC002080F31188DE +:101B700008B0BDE8F08700002DE9F84F18220446B0 +:101B80000F4604300021FFF745FA2046234B40F86A +:101B9000283BFFF747FF04F13800FFF749FF04F146 +:101BA000580804F582554646183530462036FFF76A +:101BB0003FFFAE42F9D104F580554FF480534FF00A +:101BC0000009C5E91739C5F858800123EE6604F508 +:101BD000875804F58456C5F8649085F8683085F810 +:101BE0007030183608F118084FF0000A4FF0000B5B +:101BF00046E908ABA6F11800FFF714FF203646F8B7 +:101C0000289C4645F4D185F8E07017B1044800F0EF +:101C1000C3FB044B63622046BDE8F88FC84400084C +:101C2000A04400080064004010B5044B1978044635 +:101C30004A1C1A70FFF7A0FF204610BD2C38002068 +:101C40002DE9F047002950D0294B2A4FB7FBF1F579 +:101C500099428CBF0A231123581EB5FBF3FC03FBEA +:101C60001C53C4B22BB102280346F5D80020BDE8AE +:101C7000F0870CF1FF36B6F5806FF7D2C4EBC40ED7 +:101C80000EF103034FEAE309C3F3C703A4EB030810 +:101C900009F1010A4FF47A755FFA88F009FB0555DE +:101CA0005AFA88F8B5FBF8F5B5F5617FC1BF0EF1BA +:101CB000FF33C3F3C703E01AC0B25C1C50FA84F4CC +:101CC0000CFB04F4B7FBF4F4A142CFD1013BDBB22F +:101CD0000F2BCBD80138C0B20728C7D8002110710C +:101CE00016809170D3700120C1E70846BFE700BF9E +:101CF0003F420F0000B4C40470B505460E464FF4D1 +:101D00007A746B6A5B6803F00103B34207D04FF447 +:101D10007A7001F003FD013CF3D1204670BD012033 +:101D2000FCE7000070B5426A936913F0700F17D09A +:101D300000230C4D936141F2900400EB43122244C6 +:101D400011794E0709D5890707D5416A55F82360EF +:101D50008E60117941F0040111710133032BECD134 +:101D600070BD00BFB444000873B51D46436A1646F3 +:101D70009A68D207044609D59A6801219960C2F38E +:101D80004002CDE900650021FFF760FE636A9A68B2 +:101D9000D1050BD59A684FF480719960C2F3402247 +:101DA000CDE9006501212046FFF750FE636A9A687D +:101DB000D2030BD59A684FF480319960C2F3404248 +:101DC000CDE9006502212046FFF740FE04F580536F +:101DD000D3F8DC0010B103681B699847204602B0B5 +:101DE000BDE87040FFF79EBFF8B50446466A00297B +:101DF00077D106F10C073868800775D006EB01151E +:101E00003868D5F8B00110F0040FD5F8B0011ABF4A +:101E1000C00840F00040400DA062D5F8B0C11CF0F1 +:101E2000020F1CBF40F08040A062D5F8B40106EB61 +:101E3000011100F00F0084F83400D1F8B80184F8E3 +:101E40002C00D1F8B801000A84F82D00D1F8B801AF +:101E5000000C84F82E00D1F8B801000E84F82F0091 +:101E6000D1F8BC0184F83000D1F8BC01000A84F834 +:101E70003100D1F8BC01000C84F83200D1F8BC115B +:101E8000090E84F833103821396004F1440004F15C +:101E9000280104F1340551F8046B40F8046BA942A1 +:101EA000F9D109880180C4E90E2321460023A4F852 +:101EB000403051F8383B20461B6C984704F580535E +:101EC00093F8D820D3F8DC0042F0040283F8D8203D +:101ED00010B103681B6998472046BDE8F840FFF73A +:101EE00021BF06F1100786E7F8BD000010B50446D3 +:101EF00000F05AFA02460B4652EA030102D0013AB8 +:101F000063F100030449086820B12146BDE8104090 +:101F1000FFF76ABF10BD00BF28380020F0B53021A0 +:101F200081F31188DFF848E000F58351183100246F +:101F300041F2900C00EB441565442E7977070ED4DE +:101F4000F6060CD5D1E9007697429E4107D2466A43 +:101F50005EF82470B7602E7946F004062E710134C5 +:101F6000032C01F12001E5D1002383F31188F0BD9A +:101F7000B444000808B5302383F31188FFF7D2FE7C +:101F8000002383F3118808BD2DE9F041436A04461C +:101F9000986800F0E050B0F1E05F0E4622D0F8B152 +:101FA000302383F31188002504F5845741F290080B +:101FB00004EB451343441B791A0706D50135032D5D +:101FC00007F12007F4D1012007E05B07F6D439467A +:101FD000304600F083FA0028F0D1002383F3118803 +:101FE000BDE8F0810120FBE708B5302383F31188B9 +:101FF00000F58050C06EFFF725FB002383F31188A6 +:1020000043090CBF0120002008BD0000F8B51D46A3 +:10201000002313700F4606461446FFF7E5FF80F0D5 +:102020000100387025B129463046FFF7ADFF20701A +:10203000F8BD00002DE9B8410C4615461F46804604 +:1020400000F0B2F90B462178024609B9287850B160 +:102050004046FFF763FFFFF78DFF3B462A462146C8 +:10206000FFF7D4FF0120BDE8B881000070B530262D +:1020700086F31188174B9A6D42F000729A659A6B3D +:1020800042F000729A639A6B22F000729A63002306 +:1020900083F3118800F5805494F8D83013F00105CB +:1020A00016D1A9B186F311880321132001F032FA69 +:1020B0000321142001F02EFA0321152001F02AFA41 +:1020C00094F8D83043F0010384F8D83085F31188B0 +:1020D00070BD00BF001002402DE9F04700F58055AB +:1020E00088B095F8E030012B04468846164600F289 +:1020F0008280824F57F823200AB947F82300D7F887 +:1021000000A0C4F81C8084F82060BAF1000F64D0ED +:1021100095F8E030012B70D001212046FFF7A6FF93 +:10212000302383F31188626A136823F0020313607B +:10213000626A136843F001031360636A00275F61FA +:1021400087F3118801212046FFF7D6FD002800F013 +:102150009580E86EFFF764FA04F58359BA4609F1F1 +:102160001809202200216846FEF754FF02A8FFF755 +:1021700059FCCDF818A06A4609EB07030DF1180EBB +:102180009446BCE80300F44518605960624603F1C8 +:102190000803F5D1DCF80000186020379CF8042013 +:1021A0001A71602FDDD195F8D8306FF382030027C4 +:1021B00085F8D8306A4641462046ADF80070ADF843 +:1021C00002708DF80470FFF73BFD636A48BB4FF463 +:1021D00000421A6008B0BDE8F08741F2E800FFF75E +:1021E0004FFB814610B15146FFF7C6FCC7F800907F +:1021F000B9F1000F8CD10020ECE7386803681B6B45 +:1022000098470146002887D13868FFF72FFF3868C4 +:10221000036832465B684146984700287FF47CAFEC +:10222000E9E761221A609DF802309DF803201B0641 +:10223000120402F4702203F040731343BDF800202F +:10224000C2F3090213439DF804201205022E02F482 +:10225000E0020CBF4FF0004100211343626A0B43C0 +:10226000D361636A13225A61626A136823F001031F +:10227000136039462046FFF73FFD08B9636AA6E7B9 +:1022800095F8E03093BB616AD1F8002242F0010278 +:10229000C1F80022616AD1F8002222F47C5222F0B7 +:1022A0000E02C1F80022616AD1F8002242F4606295 +:1022B000C1F80022626AC2F81432626AC2F80432BB +:1022C000626A41F6FF71C2F80C12626AC2F84032CB +:1022D000626AC2F84432636A0122C3F81C22626A4D +:1022E000D2F8003223F00103C2F8003295F8D8305A +:1022F00043F0020385F8D8306CE700BF283800208F +:1023000008B500F051F850EA0103024602D0421E1F +:1023100061F10001044B186810B10B46FFF724FD72 +:10232000BDE8084001F0B8B82838002008B5002002 +:10233000FFF7DCFDBDE8084001F0AEB808B50120AC +:10234000FFF7D4FDBDE8084001F0A6B800B59BB08A +:10235000EFF3098168226846FEF74AFEEFF3058332 +:10236000014B9B6BFEE700BF00ED00E008B5FFF7F7 +:10237000EDFF000000B59BB0EFF3098168226846CD +:10238000FEF736FEEFF30583014B5B6BFEE700BF04 +:1023900000ED00E0FEE700000FB408B5029801F080 +:1023A0006DF9FEE701F048BC01F02ABC0139C9B261 +:1023B00002299EBF00EBC1000023C0E90133704732 +:1023C000F8B51B885B0705460E4615D4044600F198 +:1023D0001807BC4210D0636853B12B682846DB6BEA +:1023E0009847A368C1B23246606898470834F0E75E +:1023F000A368002BF1D1F9E70120F8BD73B56C4655 +:1024000084E80600014600224E68D5B26EB98E6897 +:102410005EB900EBC200021D94E80300013582E8BA +:1024200003001D70012002B070BD0132032A01F1CA +:102430000801E9D10020F6E72DE9F04F89B0044604 +:10244000BDF848700E46054600F118084FF0000927 +:1024500007F004074FF0000A4FF0000BA84538D0F2 +:102460006B680BB9AB684BB157B923682046DB6B7F +:102470009847AB68C1B23246686898470835EDE7BF +:10248000B9F1000FFAD1CDE900ABADF808903346B1 +:1024900003AA06F1080E186859689446ACE80300D0 +:1024A000083373456246F6D11868CCF800009B8863 +:1024B000ACF80430FFF778FF0423ADF80830236848 +:1024C000CDE900011B6C6946204698474FF0010991 +:1024D000D4E7012009B0BDE8F08F000030B50368F3 +:1024E0000968DD0FB5EBD17F23F0604421F0604235 +:1024F0004FEAD1700BD0002BB8BFA40C0029B8BF95 +:10250000920C944202D034BF0120002030BD94428E +:1025100005D1C1F38070C3F380738342F6D1944236 +:102520002CBF00200120F1E72DE9F041456A15B9E3 +:102530004162BDE8F0814B6823F06047C3F38A46EF +:102540004FEAD37EC3F3807816EA230638BF3E46AF +:10255000AC462B465A68BEEBD27F22F060440AD0CC +:10256000002A18DAA40CB44217D19D420FD10D6095 +:10257000DEE71346EEE7A74207D102F08044C2F33C +:10258000807242450BD054B1EFE708D2EDE7CCF8AA +:1025900000100B60CDE7B44201D0B442E5D81A6810 +:1025A0009C46002AE5D11960C3E700002DE9F047F9 +:1025B000089D01F007044FEAD508224405F00705FD +:1025C00000EBD1004FF47F49944201D1BDE8F08780 +:1025D00004F0070705F0070A57453E4638BF564640 +:1025E000C6F10806111B8E4228BF0E46E10808EB13 +:1025F000D50E415C13F80EC0B94029FA06F721FA4E +:102600000AF1FFB28CEA010147FA0AF739408CEA75 +:10261000010C03F80EC034443544D5E780EA0120AC +:10262000082341F2210201B24000002980B203F1E7 +:10263000FF33B8BF504013F0FF03F4D170470000E0 +:1026400038B50C468D18A54200D138BD14F8011BD1 +:10265000FFF7E4FFF7E7000042684AB11368436000 +:102660004389818901339BB29942438138BF838179 +:102670001046704770B588B0202204460D46684663 +:102680000021FEF7C7FC20460495FFF7E5FF024650 +:1026900058B16B46054608AE1C4603CCB4422860D0 +:1026A0006960234605F10805F6D1104608B070BDF3 +:1026B000082817D909280CD00A280CD00B280CD0D0 +:1026C0000C280CD00D280CD00E2814BF4020302030 +:1026D00070470C2070471020704714207047182056 +:1026E0007047202070470000082817D90C280CD903 +:1026F00010280CD914280CD918280CD920280CD94A +:1027000030288CBF0F200E207047092070470A2008 +:1027100070470B2070470C2070470D207047000059 +:102720002DE9F843078C072F04461ED9D0E90298FB +:1027300000254FF6FF73C5F12006A5F1200029FA08 +:1027400005F108FA06F628FA00F031430143C9B250 +:102750001846FFF763FF0835402D0346EBD1E169CA +:102760003A46BDE8F843FFF76BBF4FF6FF70BDE890 +:10277000F883000010B54B6823B9CA8A63F30902D5 +:10278000CA8210BD04691A681C600361C38A013BD8 +:10279000C3824A60EFE700002DE9F84F1D46CB8A5F +:1027A0000F46C3F309010529814692460B4630D0F6 +:1027B0000020AAB207F11A049EB2042E1FFA80F874 +:1027C0000FD8904503F1010306D3FB8A0A4462F354 +:1027D0000903FB8201201AE01AF80060E654013078 +:1027E000EAE79045F1D2A1F1050B1C237C68BBFB05 +:1027F000F3F203FB12BB1FFA8BF6002C45D14846BF +:10280000FFF72AFF044638B978606FF00200BDE890 +:10281000F88F4FF00008E6E7002606607860ADB25A +:102820004FF0000B454510D90AEB0803221D13F8A1 +:10283000011B9155B1B208F101081B291FFA88F854 +:102840002BD0454506F10106F1D8FB8AC3F30902F6 +:10285000154465F30903BCE7013292B21C462368B4 +:10286000002BF9D16B1F0B441C21B3FBF1F3013397 +:102870009BB29A42D3D2BBF1000FD0D14846FFF7AA +:10288000EBFE20B9C4F800B0BFE70122E7E7C0F8CB +:1028900000B05E4620600446C1E74545D5D94846AC +:1028A000FFF7DAFE08B92060AFE7C0F800B00026F5 +:1028B00020600446B6E700002DE9F04F2DED028BB5 +:1028C0001C4683B05B69019207468846002B00F0E6 +:1028D000A780238C2BB1E269002A00F0A180072B8E +:1028E00035D807F10C00FFF7B7FE054638B96FF091 +:1028F0000205284603B0BDEC028BBDE8F08F142220 +:102900000021FEF787FB228CE16905F10800FEF744 +:102910006FFB208C013080B2FFF7E6FEFFF7C8FEA8 +:10292000013880B22084013028746369228C1B78BE +:102930002A4403F01F0363F03F0348F00041137281 +:10294000384669602946FFF7EFFD0125D1E70233DC +:102950009BB20722C18A0633B3FBF2F3828A521A72 +:102960009BB292B29342C2D800F10C034FF000091F +:1029700008EE103A4FF0800A4E464D4618EE100A07 +:10298000FFF76AFE83460028B1D014220021FEF72B +:1029900041FB002E3AD1019BABF8083002220BF12B +:1029A000080E1FFA82FC0CF10100BCF1060F218C0D +:1029B00080B201D88E422BD3FFF796FEFFF778FE48 +:1029C00062691278013802F01F028E4208BF4FF090 +:1029D000400A42EA49121BFA80F14AEA020A01302F +:1029E00048F0004281F808A08BF81000CBF80420D2 +:1029F00059463846FFF798FD238C0135B3422DB276 +:102A000089F001094FF0000AB8D172E70022C6E749 +:102A1000E169895D0EF802100136B6B20132C0E7F5 +:102A20006FF0010565E70000F8B515460E46302247 +:102A3000002104461F46FEF7EDFA069B6360B5F5DC +:102A4000001F079BA76034BF6A094FF6FF72A3629D +:102A500097B2E66104F1100000239A4206D80023E1 +:102A60000360A782E3822383E360F8BD066001333D +:102A700030462036F1E7000003781BB94BB2002B3B +:102A8000C8BF01707047000000787047F8B50C4669 +:102A9000C969074611B9238C002B37D1257E1F2D1C +:102AA00034D8387828BB228C072A2CD8268A36F0CE +:102AB00003032BD14FF6FF70FFF7C2FD20F001009A +:102AC0003102400441EA0561400C41EA40254FF6DD +:102AD000FF72234629463846FFF7EEFE002807DD41 +:102AE000626913780133DBB21F2B88BF0023137098 +:102AF000F8BD218A2D0645EA012505432046FFF74A +:102B00000FFE0246E5E76FF00300F1E76FF001000A +:102B1000EEE7000070B58AB0044616460021282270 +:102B200068461D46FEF776FABDF83830ADF810302D +:102B30000F9B05939DF840308DF81830119B07933B +:102B40006946BDF84830ADF820302046CDE9026531 +:102B5000FFF79CFF0AB070BD2DE9F041D36905462F +:102B60000C4616460BB9138C5BBB377E1F2F28D83B +:102B700095F80080B8F1000F26D03046FFF7D0FD61 +:102B80003378210241EAC33141EA0801338A41EA3C +:102B9000076141EA03410246334641F0800128467D +:102BA000FFF78AFE00280ADD3378012B07D172690E +:102BB00013780133DBB21F2B88BF00231370BDE8ED +:102BC000F0816FF00100FAE76FF00300F7E7000013 +:102BD000F0B58BB004460D46174600212822684602 +:102BE0001E46FEF717FA9DF84C305A1E53425341C9 +:102BF0008DF800309DF84030ADF81030119B0593F2 +:102C00009DF848308DF81830149B07936A46BDF83C +:102C10005430ADF8203029462046CDE90276FFF742 +:102C20009BFF0BB0F0BD0000406A00B1043070475C +:102C3000436A1A68426202691A600361C38A013BEF +:102C4000C38270472DE9F041D0F82080194E144618 +:102C50001D464146002709B9BDE8F081D1E90223AC +:102C6000A21A65EB0303964277EB03031ED2036AB5 +:102C70008B420DD1FFF77EFD036A1B680362036977 +:102C80000B60C38A0161016A013BC3828846E2E7A7 +:102C9000FFF770FD0B68C8F8003003690B60C38A4A +:102CA0000161013BC382D8F80010D4E78846096867 +:102CB000D1E700BF80841E002DE9F04F8BB00D4698 +:102CC000DDF8509014469B468046002800F019819C +:102CD000B9F1000F00F01581531E3F2B00F2118156 +:102CE000012A03D1BBF1000F40F00B810023CDE995 +:102CF0000833B8F81430B5EBC30F4FEAC30703D35A +:102D000000200BB0BDE8F08F2B199F42D8F80C3093 +:102D10003ABF7F1BFFB227461BB9D8F81030002BF3 +:102D20007AD0272D4ED8C5F12806B7424FF00003C0 +:102D30002CBFF6B23E4600932946D8F8080008ABEF +:102D40003246FFF733FCA7EB060A35445FFA8AFAEE +:102D5000B8F8143003F10053053BDB000493D8F8B6 +:102D60000C3003932821039B13B1BAF1000F2CD12F +:102D7000D8F8100040B1BAF1000F05D0009608ABAA +:102D80005246691AFFF712FC38B2002FB8D0660716 +:102D90000AD00AAB03EBD401624211F8083C02F0FE +:102DA0000702134101F8083C082C3CD9102C40F2D2 +:102DB000B580202C40F2B780BBF1000F00F09C8062 +:102DC000082334E0BA460026C2E7049BE02B28BF64 +:102DD000E02306930B44AB42059314D95A1B039886 +:102DE0000096924534BF5246D2B2691A08AB0430FD +:102DF0000792FFF7DBFB079A1644AAEB020A154479 +:102E0000F6B25FFA8AFA049B069A05999B1A049314 +:102E1000039B1B680393A6E70093D8F8080008AB50 +:102E20003A462946AEE7BBF1000F13D00123B4EBBD +:102E3000C30F6CD0082C12D89DF82030621E23FAE4 +:102E400002F2D50706D54FF0FF3202FA04F423430D +:102E50008DF820309DF8203089F8003051E7102C93 +:102E600012D8BDF82030621E23FA02F2D10706D52F +:102E70004FF0FF3202FA04F42343ADF82030BDF8DE +:102E80002030A9F800303CE7202C0FD80899631EA9 +:102E900021FA03F3DA0705D54FF0FF3202FA04F402 +:102EA0000C430894089BC9F800302AE7402C2BD02B +:102EB000DDE90865611EC4F12102A4F1210326FAAF +:102EC00001F105FA02F225FA03F311431943CB0786 +:102ED00012D50122A4F12003C4F1200102FA03F368 +:102EE00022FA01F1A240524243EA010363EB430399 +:102EF00032432B43CDE90823DDE90823C9E9002348 +:102F0000FFE66FF00100FCE66FF00800F9E6082C20 +:102F1000A0D9102CB3D9202CEED8C3E7BBF1000FF9 +:102F2000ADD0022383E7BBF1000FBBD004237EE7C3 +:102F300030B5012A144638BF0124402C85B028BF83 +:102F400040240025012ACDE9025518D81B788DF8B8 +:102F5000083063070AD004AB03EBD405624215F8CE +:102F6000083C02F00702934005F8083C0091034634 +:102F70002246002102A8FFF719FB05B030BD082A40 +:102F8000E4D9102A03D81B88ADF80830E1E7202ADD +:102F90008DBFD3E900231B680293CDE90223D8E754 +:102FA00010B5CB681BB98B600B618B8210BD0469B7 +:102FB0001A681C600361C38A013BC382CA60F0E7E0 +:102FC00003064CBFC0F3C0300220704708B502466C +:102FD000FFF7F6FF022806D15306C2F30F2001D1F6 +:102FE00000F0030008BDC2F30740FBE72DE9F04FF6 +:102FF00093B0CDE903230A6804461046FFF7E0FFCB +:10300000022814BFC2F306260026002A0D46824677 +:1030100080F2F78112F0C04940F0F381097B00296A +:1030200000F0EF81022803D02378B34240F0EC8116 +:10303000C2F304630693104602F07F030593FFF783 +:10304000C5FF059B29444FEA834848EA0A4848EAF5 +:103050004668CE7800230022CDE90823F309834691 +:1030600048EA0008029367D0059B00930246676810 +:10307000534608A92046B847002800F0C881276AAF +:103080004FB9414604F10C00FFF7F4FA074690B936 +:103090006FF0020054E03B6998450DD03F68002F67 +:1030A000F9D1414604F10C00FFF7E4FA0746002885 +:1030B000EED0236A3B60276297F817C006F01F081E +:1030C000CCF3840CACEB08001FFA80FE0028B8BFDC +:1030D0000EF12000A8EB0C031FFA83FED7E90221B2 +:1030E000B8BF00B2002B0793BEBF0EF120031BB286 +:1030F000079352EA010338D0039BDFF824E39A1ABE +:10310000049B4FF0000C63EB010196457CEB01033F +:103110002BD36B7B97F81AE0734519D1029B002BD8 +:1031200078D0012821DC7868F8B9DFF8F0C294453E +:1031300070EB010316D337E0276A27B96FF00C0054 +:1031400013B0BDE8F08F3B699845B5D03F68F4E710 +:10315000B24890427CEB010301D30020F0E7029BD0 +:10316000002BFAD0079B0F2B17DCFA7DB30002F07F +:10317000030203F07C031343FB7539462046FFF737 +:10318000F9FA6B7BBB76029B3BB9FB7DC3F38402F0 +:10319000013262F38603FB75D0E76A7BBB7E9A42FD +:1031A000DBD1029B002B35D0B309022B32D0039B1D +:1031B000BB60049BFB60142200210DA8FDF72AFFD1 +:1031C000039B0A93049B0B932B1D0C932B7BADF855 +:1031D0003EB0013BDBB2ADF83C30069B8DF842308F +:1031E000059B8DF8433094F82C308DF840A083F087 +:1031F00001038DF844308DF84180A3680AA9204668 +:103200009847FB7DC3F38403013303F01F039B0244 +:10321000FB82A2E7FB7DC6F34012B2EBD31F40F066 +:10322000F980C3F38403434540F0FC80029A2B7B72 +:10323000B609002A52D016F0010661D1032B40F2E4 +:10324000F480039BBB60049BFB60FB8A66F309036D +:10325000FB822B7BAE1D033BDBB23246394604F1C9 +:103260000C00FFF799FA00280CDA39462046FFF7E0 +:1032700081FAFB7DC3F38403013303F01F039B0238 +:10328000FB8205E7DDE90884AB883B834FF6FF73DB +:10329000C9F12000A9F1200228FA09F104FA00F08E +:1032A000014324FA02F211431846C9B2FFF7B6F9F6 +:1032B00009F10809B9F1400F0346E9D1B8822A7B28 +:1032C000033AD2B23146FFF7BBF9FB7DB882DA434D +:1032D000C2F3C01262F3C713FB753EE786B92E1D19 +:1032E000013BDBB23246394604F10C00FFF754FAD9 +:1032F0000028BADB2A7BB88A013AD2B23146E2E72B +:10330000F98AC1F30901013B0429DAB25BD8281D0F +:10331000002307F11B069A4208D910F801CB06F8E2 +:1033200001C0013101330529DBB2F4D103990A91BF +:1033300004990B91934207F11B010C9138BF0433A0 +:1033400079680D9134BF55FA83F300230E93FB8AFD +:10335000ADF83EB0C3F309031A44069B8DF8423022 +:10336000059B8DF8433094F82C30ADF83C2083F069 +:1033700001038DF8443000238DF840A08DF8418082 +:103380007B602A7BB88A013A291DFFF759F93B8BEC +:10339000B882834203D1A3680AA9204698472046F1 +:1033A0000AA9FFF7FDFDFB7DBA8AC3F3840301334D +:1033B00003F01F039B02FB823B8B9A420CBF002051 +:1033C0006FF01000BCE67B68002BAFD0052001E059 +:1033D0001C3033461E68002EFAD1091A081D2E1D16 +:1033E000184401EB090CBCF11B0F5FFA89F39DD85F +:1033F0009A429BD916F8013B00F8013B09F10109FB +:10340000EFE76FF009009BE66FF00A0098E66FF0B7 +:103410000B0095E66FF00D0092E600BF40420F00F2 +:1034200080841E006FF00E008AE66FF00F0087E6C2 +:10343000EFF3098305494A6B22F001024A636833BE +:1034400083F30988002383F31188704700EF00E0BD +:10345000302080F3118862B60C4B0D4AD96821F4F4 +:10346000E0610904090C0A43DA60D3F8FC20094939 +:1034700042F08072C3F8FC200A6842F001020A6040 +:103480002022DA7783F82200704700BF00ED00E0C9 +:103490000003FA05001000E010B5302383F3118813 +:1034A0000E4B5B6813F4006314D0F1EE103AEFF3A7 +:1034B0000984683C4FF08073E361094BDB6B236642 +:1034C00084F3098800F0A4F810B1064BA36110BD85 +:1034D000054BFBE783F31188F9E700BF00ED00E03F +:1034E00000EF00E0FF020008020300084FF0E023B5 +:1034F000002258684FF0FF31930003F1604303F559 +:10350000614301329042C3F88010C3F88011F3D2B6 +:103510007047000000F1604303F561430901C9B23F +:1035200083F80013012200F01F039A4043099B0017 +:1035300003F1604303F56143C3F880211A607047CB +:1035400000230375826803691B6899689142FBD266 +:103550005A6803604260106058607047002303752A +:10356000826803691B6899689142FBD85A680360B6 +:10357000426010605860704708B50846302383F3F6 +:1035800011880B7D032B05D0042B0DD02BB983F3B1 +:10359000118808BD8B6900221A604FF0FF338361E8 +:1035A000FFF7CEFF0023F2E7D1E9003213605A6043 +:1035B000F3E70000FFF7C4BF054BD968087518682A +:1035C00002681A60536001220275D860FCF782BE5F +:1035D0003838002030B50C4BDD684B1C87B00446F2 +:1035E0000FD02B46094A684600F02AF92046FFF71B +:1035F000E3FF009B13B1684600F02CF9A86907B0FF +:1036000030BDFFF7D9FFF9E73838002079350008D9 +:10361000044B1A68DB6890689B68984294BF00204E +:103620000120704738380020084B10B51C68D86856 +:1036300022681A60536001222275DC60FFF78EFF5A +:1036400001462046BDE81040FCF744BE3838002053 +:1036500038B5074C074908480123002523706560E9 +:1036600000F0EAFB0223237085F3118838BD00BF08 +:10367000603A0020104500083838002008B572B6BE +:10368000044B186500F0ACFA00F058FB024B032223 +:103690001A70FEE738380020603A002000F010B9B8 +:1036A0008B60022308618B82084670478368A3F110 +:1036B000840243F8142C026943F8442C426943F80D +:1036C000402C094A43F8242CC26843F8182C0222E3 +:1036D00003F80C2C002203F80B2C044A43F8102C9E +:1036E000A3F12000704700BFED0200083838002029 +:1036F00008B5FFF7DBFFBDE80840FFF75BBF000040 +:10370000024BDB6898610F20FFF756BF3838002066 +:10371000302383F31188FFF7F3BF000008B501469B +:10372000302383F311880820FFF754FF002383F32D +:10373000118808BD10B503689C68A2420CD85C686B +:103740008A600B604C602160596099688A1A9A609F +:103750004FF0FF33836010BD1B68121BECE70000C5 +:103760000A2938BF0A2170B504460D460A26601999 +:1037700000F05CFB00F048FB041BA54203D8751C5D +:103780002E460446F3E70A2E04D9BDE87040012016 +:1037900000F092BB70BD0000F8B5144B0D46D96126 +:1037A00003F1100141600A2A1969826038BF0A22B8 +:1037B000016048601861A818144600F029FB0A2728 +:1037C00000F022FB431BA342064606D37C1C2819AB +:1037D00000F02CFB27463546F2E70A2F04D9BDE856 +:1037E000F840012000F068BBF8BD00BF3838002069 +:1037F000F8B506460D4600F007FB0F4A134653F88E +:10380000107F9F4206D12A4601463046BDE8F84067 +:10381000FFF7C2BFD169BB68441A2C1928BF2C46D8 +:10382000A34202D92946FFF79BFF224631460348AF +:10383000BDE8F840FFF77EBF383800204838002048 +:1038400010B4C0E9032300235DF8044B4361FFF784 +:10385000CFBF000010B5194C236998420DD0D0E9B4 +:103860000032816813605A609A680A449A600023A3 +:1038700003604FF0FF33A36110BD2346026843F895 +:10388000102F53600022026022699A4203D1BDE8E2 +:10389000104000F0C5BA936881680B44936000F053 +:1038A000B3FA2269E1699268441AA242E4D9114448 +:1038B000BDE81040091AFFF753BF00BF3838002099 +:1038C0002DE9F047DFF8BC8008F110072C4ED8F83E +:1038D000105000F099FAD8F81C40AA68031B9A42CD +:1038E0003ED81444D5E900324FF00009C8F81C4016 +:1038F00013605A60C5F80090D8F81030B34201D177 +:1039000000F08EFA89F31188D5E9033128469847EB +:10391000302383F311886B69002BD8D000F074FA40 +:103920006A69A0EB04094A4582460DD2022000F0E4 +:10393000C3FA0022D8F81030B34208D151462846C5 +:10394000BDE8F047FFF728BF121A2244F2E712EB56 +:10395000090938BF4A4629463846FFF7EBFEB5E766 +:10396000D8F81030B34208D01444211AC8F81C000B +:10397000A960BDE8F047FFF7F3BEBDE8F08700BFE0 +:10398000483800203838002038B500F03DFA054AA4 +:10399000D2E90845031B181945F10001C2E90801E5 +:1039A00038BD00BF3838002000207047FEE7000017 +:1039B000704700004FF0FF3070470000BFF34F8F9B +:1039C000024A1369DB03FCD4704700BF00200240A9 +:1039D00008B5094B1B7873B9FFF7F0FF074B5A691D +:1039E000002ABFBF064A9A6002F188329A601A68BC +:1039F00022F480621A6008BD783A0020002002405C +:103A00002301674508B50B4B1B7893B9FFF7D6FF29 +:103A1000094B5A6942F000425A611A6842F48052D6 +:103A20001A601A6822F480521A601A6842F480629E +:103A30001A6008BD783A0020002002407F289ABF13 +:103A400000F58030C0020020704700004FF4006095 +:103A500070470000802070477F2808B50BD8FFF71B +:103A6000EDFF00F500630268013204D104308342A7 +:103A7000F9D1012008BD0020FCE700007F2810B527 +:103A800004461FD8FFF79AFFFFF7A2FF0E4BF32261 +:103A90001A6102225A615A6942EAC0025A615A699D +:103AA00042F480325A61FFF789FF4FF40061FFF75B +:103AB000C5FF00F03FF9FFF7A5FF2046BDE8104025 +:103AC000FFF7CABF002010BD002002402DE9F843D7 +:103AD00040EA020313F00703144606D0304B40F2CD +:103AE00082321A600020BDE8F88385182D4A95427D +:103AF0000CD92B4A40F287311160F3E7031D1B6894 +:103B00004A68934208D1083C08300831072C14D980 +:103B100002680B689A42F1D0FFF75AFFFFF74EFF99 +:103B2000214E08314FF001084FF00009012CA1F19E +:103B3000080706D8FFF766FF01E0002CECD1012052 +:103B4000D1E7C6F81480054651F8083C45F8043B17 +:103B500051F8043C4360FFF731FF336943F0010340 +:103B60003361C6F81490026851F8083C9A420CD0B0 +:103B70000B4B40F2AF321A600C4B18600C4B1C60C0 +:103B80000C4B1F60FFF73EFFACE72D6851F8043C7B +:103B90009D4201F10801EBD1083C0830C6E700BFA7 +:103BA000743A00200000040800200240683A002017 +:103BB000703A00206C3A0020084908B50B7828B10B +:103BC0001BB9FFF705FF01230B7008BD002BFCD0CC +:103BD000BDE808400870FFF715BF00BF783A002025 +:103BE00002484FF47F4100F0A7B800BF0001002059 +:103BF0000846114600F0E2BB084600F0F5BB0000A5 +:103C000038B5EFF311859DB9EFF30584C4F30804CB +:103C1000302334B183F31188FFF7B6FE85F31188A2 +:103C200038BD83F31188FFF7AFFE84F3118838BDE8 +:103C3000BDE83840FFF7A8BE38B5FFF7E1FF114CEB +:103C4000114AC00840EA4170A0FB025EC908A0FB0F +:103C5000040C1CEB050CA1FB04404FF000035B417E +:103C6000A1FB02121CEB040C43EB000011EB0E0154 +:103C700042F10002411842F10000090941EA0070D6 +:103C800038BD00BFCFF753E3A59BC42010B5024455 +:103C9000064BD2B2904200D110BD441C00B253F882 +:103CA000200041F8040BE0B2F4E700BF50280040C8 +:103CB000114B30B5D3F89040240409D4D3F8904088 +:103CC000C3F89040D3F8904044F40044C3F89040C7 +:103CD0000A4C236843F4807323600244084BD2B239 +:103CE000904200D130BD441C00B251F8045B43F84F +:103CF0002050E0B2F4E700BF001002400070004026 +:103D00005028004007B5012201A90020FFF7BEFF9F +:103D1000019803B05DF804FB13B50446FFF7F2FF0A +:103D2000A04205D0012201A900200194FFF7C0FFA5 +:103D300002B010BD704700007047000070470000DF +:103D4000074B45F255521A6003225A6040F2FF7247 +:103D50009A604CF6CC421A60024B01221A707047EE +:103D600000300040803A0020034B1B781BB1034B0E +:103D70004AF6AA221A607047803A002000300040BC +:103D8000054B1A6832B902F1804202F50432D2F8CA +:103D900094201A60704700BF7C3A0020024B4FF419 +:103DA0000002C3F8942070470010024008B5FFF7E6 +:103DB000E7FF024B1868C0F3407008BD7C3A002052 +:103DC00070470000FEE700000A4B0B480B4A904288 +:103DD0000BD30B4BDA1C121AC11E22F003028B42CA +:103DE00038BF00220021FDF715B953F8041B40F835 +:103DF000041BECE7A4450008043B0020043B002022 +:103E0000043B002000F0BEB84FF08043586A704772 +:103E10004FF08043002258631A610222DA60704733 +:103E20004FF080430022DA60704700004FF080437B +:103E300058637047FEE7000070B51B4B0163002517 +:103E4000044686B0586085620E46FFF701FB04F118 +:103E50001003C4E904334FF0FF33C4E90635C4E965 +:103E60000044A560E562FFF7CFFF2B460246C4E998 +:103E7000082304F134010D4A256580232046FFF70D +:103E80000FFC0123E0600A4A0375009272680192F8 +:103E9000B268CDE90223074B6846CDE90435FFF748 +:103EA00027FC06B070BD00BF603A00201C4500082A +:103EB00021450008353E0008024AD36A1843D06203 +:103EC000704700BF38380020244B2548DA6A42F09A +:103ED000070210B4DA62DA6A224C22F00702DA62D0 +:103EE000DA6ADA6C42F00702DA64DA6E42F007024C +:103EF000DA664FF09042DB6E4FF0AA310023536038 +:103F00009160D0604FF6FF7050611362536214608D +:103F10001024C2F80434C2F80814C2F80C444FF656 +:103F2000F774C2F814449924C2F82034C2F8244427 +:103F30000D4CC2F80044C2F80438C2F80818C2F8A0 +:103F40000C38C2F81408C2F82038C2F82438C2F875 +:103F500000385DF8044B00F055B800BF0010024077 +:103F6000000100240001002850000A0008B500F0FC +:103F700005FAFFF76DFBBDE80840FFF701BF000041 +:103F8000704700000F4B9A6D42F001029A659A6FDC +:103F900042F001029A670C4A9B6F936843F0010359 +:103FA00093604FF080434F229A624FF0FF32DA6203 +:103FB00000229A615A63DA605A6001225A611A60DB +:103FC000704700BF00100240002004E04FF0804224 +:103FD00008B51169D3680B40D9B2C9439B07116179 +:103FE00007D5302383F31188FFF758FB002383F3B1 +:103FF000118808BD08B5FFF779FABDE8084000F060 +:1040000099B900005A4B4FF0FF319A6A99629A6A47 +:1040100000229A62986AD86A60F00700D862D86A6B +:1040200000F00700D862D86A186B1963186B1A631E +:10403000186B986B9963986B9A63986BD86BD9637C +:10404000D86BDA63D86B186C1964196C1A641A6C23 +:10405000484A4FF4E06111601A6E474942F001028C +:104060001A66D3F8802022F00102C3F88020D3F82A +:1040700080209A6D42F080529A659A6F22F08052A9 +:104080009A679A6F4FF440720A604A6912F480622C +:10409000FBD14A601A6822F0F00242F060021A6016 +:1040A0001A6842F001021A601A689107FCD50022D2 +:1040B0009A609A6812F00C02FBD1D3F8901011F4B8 +:1040C000407F1EBF4FF48031C3F89010C3F890209A +:1040D00061221A601A689207FCD500229A609A68D9 +:1040E00012F00C0FFBD169221A60D3F8942022F44D +:1040F000706242F4C062C3F894201A6842F48032BD +:104100001A601A689003FCD5D3F8902022F003229D +:10411000C3F89020194ADA601A6842F080721A6077 +:104120001A689101FCD5164A1A611A6842F0806239 +:104130001A601A681201FCD500229A600D49114AD2 +:10414000C3F888200A6822F0070242F004020A60DD +:104150000A6802F00702042AFAD19A6842F00302C0 +:104160009A609A6802F00C020C2AFAD1704700BFDC +:1041700000100240002002400070004003140001C3 +:10418000000C100055550134074A08B5536903F077 +:104190000103536123B1054A13680BB15068984776 +:1041A000BDE80840FFF778B900040140843A0020D8 +:1041B000074A08B5536903F00203536123B1054A66 +:1041C00093680BB1D0689847BDE80840FFF764B921 +:1041D00000040140843A0020074A08B5536903F0FF +:1041E0000403536123B1054A13690BB15069984721 +:1041F000BDE80840FFF750B900040140843A0020B0 +:10420000074A08B5536903F00803536123B1054A0F +:1042100093690BB1D0699847BDE80840FFF73CB9F6 +:1042200000040140843A0020074A08B5536903F0AE +:104230001003536123B1054A136A0BB1506A9847C2 +:10424000BDE80840FFF728B900040140843A002087 +:10425000164B10B55C6904F478725A61A30604D554 +:10426000134A936A0BB1D06A9847600604D5104A86 +:10427000136B0BB1506B9847210604D50C4A936B16 +:104280000BB1D06B9847E20504D5094A136C0BB10A +:10429000506C9847A30504D5054A936C0BB1D06CBC +:1042A0009847BDE81040FFF7F7B800BF0004014091 +:1042B000843A0020194B10B55C6904F47C425A61C1 +:1042C000620504D5164A136D0BB1506D984723054E +:1042D00004D5134A936D0BB1D06D9847E00404D513 +:1042E0000F4A136E0BB1506E9847A10404D50C4AC7 +:1042F000936E0BB1D06E9847620404D5084A136FD1 +:104300000BB1506F9847230404D5054A936F0BB146 +:10431000D06F9847BDE81040FFF7BEB800040140D9 +:10432000843A002008B5FFF751FEBDE80840FFF7CA +:10433000B3B80000062108B50846FFF7EBF80621E0 +:104340000720FFF7E7F806210820FFF7E3F806212A +:104350000920FFF7DFF806210A20FFF7DBF8062126 +:104360001720FFF7D7F806212820FFF7D3F8BDE87C +:10437000084007211C20FFF7CDB8000008B5FFF763 +:1043800039FE00F007F8FFF7FBFDBDE80840FFF736 +:1043900039BD00000023054A19460133102BC2E93C +:1043A000001102F10802F8D1704700BF843A0020E2 +:1043B0000B460146184600F009B80000024B0A46B9 +:1043C00001461868FFF714BC1811002010B5054C01 +:1043D00013462CB10A4601460220AFF3008010BDFF +:1043E0002046FCE700000000024B01461868FFF77A +:1043F00003BC00BF1811002010B5013902449042DF +:1044000001D1002005E0037811F8014FA34201D04B +:10441000181B10BD0130F2E72DE9F041A3B1C91A14 +:1044200017780144044603F1FF3C8C42204601D931 +:10443000002009E00578BD4204F10104F5D10CEB40 +:104440000405D618A54201D1BDE8F08115F8018D0B +:1044500016F801EDF045F5D0E7E70000034611F846 +:10446000012B03F8012B002AF9D170476F72672ED8 +:104470006172647570696C6F742E5442532D4C34A4 +:1044800033312D50657269706800000040A2E4F17C +:10449000646891060041A3E5F26569920700000097 +:1044A0004261642043414E496661636520696E64E0 +:1044B00065782E0080000000008000000000800071 +:1044C000000000000000000095180008D920000836 +:1044D00035200008D5180008E1180008ED1A00087A +:1044E000A5180008B5180008A9180008B118000898 +:1044F000AD180008091A0008B9180008FD230008C3 +:10450000AD230008C9180008DD1900086330000059 +:104510000C45000890380020603A00206D61696EFB +:104520000069646C650000002604000000000000C3 +:104530000060030000000000FE2A0100D204000019 +:104540001C1100200000000000000000000000001E +:10455000000000000000000000000000000000005B +:10456000000000000000000000000000000000004B +:10457000000000000000000000000000000000003B +:10458000000000000000000000000000000000002B +:10459000000000000000000000000000000000001B +:0445A0000000000017 +:00000001FF From e5f719b65a7fc30740b285fd656626b476df8de6 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 30 Jan 2025 23:25:14 +1030 Subject: [PATCH 25/85] Copter: SystemID: Fix unutilized variables --- ArduCopter/mode_systemid.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 1462454b78279b..995330559393cf 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -161,7 +161,8 @@ void ModeSystemId::exit() // should be called at 100hz or more void ModeSystemId::run() { - float target_roll, target_pitch; + float target_roll = 0.0f; + float target_pitch = 0.0f; float target_yaw_rate = 0.0f; float pilot_throttle_scaled = 0.0f; float target_climb_rate = 0.0f; From 2cd3970e3620a2770fdbe8e0b2d528d9db65dcc8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 1 Feb 2025 23:00:43 +1100 Subject: [PATCH 26/85] GCS_MAVLink: add capability to send autopilot to config error loop Co-authored-by: Bob Long Co-authored-by: Michelle Rossouw another one of our "do nasty thing to autopilot" commands, useful for testing what ground control stations do when the autopilot is in this state --- libraries/GCS_MAVLink/GCS_Common.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 28df0943fd8eb0..41edb3152ae369 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3469,6 +3469,11 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac send_text(MAV_SEVERITY_WARNING,"deadlock passed"); return MAV_RESULT_ACCEPTED; } + if (is_equal(packet.param4, 101.0f)) { + // the capital-U and ~ here are actually important for + // testing a MissionPlanner bug! + AP_BoardConfig::config_error("YOU~RE WELCOME!"); + } #endif // AP_MAVLINK_FAILURE_CREATION_ENABLED #if HAL_ENABLE_DFU_BOOT From 5790e0e38e65f5776b5733d78652504329b4a54d Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Fri, 31 Jan 2025 09:14:00 +0530 Subject: [PATCH 27/85] AP_HAL_ChibiOS: use AP_PERIPH_RANGEFINDER_ENABLED in place of HAL_PERIPH_ENABLE_RANGEFINDER --- libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 8 +++++++- libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat | 2 +- 11 files changed, 17 insertions(+), 11 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat index cc045994a16024..cb7303811768f7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -125,7 +125,7 @@ define HAL_WITH_ESC_TELEM 1 define AP_SERIALLED_ENABLED 1 # Rangefinder -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 # disable rangefinder by default define AP_PERIPH_RANGEFINDER_PORT_DEFAULT -1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat index ccf11cb8932317..6df702eb61d3f4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/hwdef.dat @@ -64,5 +64,5 @@ define HAL_PROXIMITY_ENABLED 1 # ----------- rangefinder -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat index 33045cf9343bc3..5525c9a0f580a0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat @@ -21,7 +21,7 @@ define AP_PERIPH_MAG_ENABLED 1 define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED define HAL_PERIPH_ENABLE_ADSB -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT define AP_PERIPH_BATTERY_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat index 99e189f4b3b39c..a193955cc77718 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat @@ -5,7 +5,7 @@ define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE # support all rangefinder types -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 define RANGEFINDER_MAX_INSTANCES 2 define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat index 317c017ecc522d..db079fb2542239 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat @@ -73,7 +73,7 @@ define AP_PERIPH_BARO_ENABLED 1 define AP_PERIPH_BATTERY_ENABLED 1 define HAL_PERIPH_ENABLE_RC_OUT -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 1 define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat index f5d9a57489d9d0..2586e78a8f6fb7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat @@ -4,7 +4,7 @@ include ../f103-periph/hwdef.inc define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index 3aad3bfa13bb97..6c0fb64a274567 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -125,7 +125,7 @@ define AP_PERIPH_GPS_ENABLED 1 define AP_PERIPH_MAG_ENABLED 1 define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 define HAL_PERIPH_ENABLE_MSP # setup for MSP diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat index ba9aaf55fc846e..a9552b3becdb61 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat @@ -11,7 +11,7 @@ define AP_PERIPH_BARO_ENABLED 1 define HAL_PERIPH_ENABLE_AIRSPEED define HAL_PERIPH_ENABLE_ADSB define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 # allow for F9P GPS modules with moving baseline define GPS_MOVING_BASELINE 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat index 02d67155b26894..05727707bd9563 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat @@ -175,7 +175,7 @@ define HAL_MSP_ENABLED 1 define AP_PERIPH_MSP_PORT_DEFAULT 4 # ----------------- rangefinder,ADSB ---------------------- -define HAL_PERIPH_ENABLE_RANGEFINDER +define AP_PERIPH_RANGEFINDER_ENABLED 1 # disable rangefinder by default define AP_PERIPH_RANGEFINDER_PORT_DEFAULT -1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index a2cc8b797c9a21..6fc43ed702b05b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -178,6 +178,9 @@ #ifdef HAL_PERIPH_ENABLE_BARO #error "Change 'define HAL_PERIPH_ENABLE_BARO' to 'define AP_PERIPH_BARO_ENABLED 1'" #endif +#ifdef HAL_PERIPH_ENABLE_RANGEFINDER +#error "Change 'define HAL_PERIPH_ENABLE_RANGEFINDER' to 'define AP_PERIPH_RANGEFINDER_ENABLED 1'" +#endif /* * defaults for various AP_Periph features: @@ -200,6 +203,9 @@ #ifndef AP_PERIPH_BARO_ENABLED #define AP_PERIPH_BARO_ENABLED 0 #endif +#ifndef AP_PERIPH_RANGEFINDER_ENABLED +#define AP_PERIPH_RANGEFINDER_ENABLED 0 +#endif /* * turning on of ArduPilot features based on which AP_Periph features @@ -210,6 +216,7 @@ #define AP_AHRS_ENABLED AP_PERIPH_AHRS_ENABLED #define AP_COMPASS_ENABLED AP_PERIPH_MAG_ENABLED #define AP_BARO_ENABLED AP_PERIPH_BARO_ENABLED +#define AP_RANGEFINDER_ENABLED AP_PERIPH_RANGEFINDER_ENABLED /* * GPS Backends - we selectively turn backends on. @@ -395,7 +402,6 @@ #define AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED 0 #endif -#define AP_RANGEFINDER_ENABLED defined(HAL_PERIPH_ENABLE_RANGEFINDER) #define AP_RPM_ENABLED defined(HAL_PERIPH_ENABLE_RPM) #define AP_RCPROTOCOL_ENABLED defined(HAL_PERIPH_ENABLE_RCIN) #define AP_RTC_ENABLED defined(HAL_PERIPH_ENABLE_RTC) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat index 71ca1877459945..fc2d9d46acc696 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/sw-spar-f407/hwdef.dat @@ -91,7 +91,7 @@ define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 # rangefinder -define HAL_PERIPH_ENABLE_RANGEFINDER 2 +define AP_PERIPH_RANGEFINDER_ENABLED 1 define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 2 # compass From c32414386698c425d8721dbe3f6b1ec33f1deb79 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Fri, 31 Jan 2025 09:14:38 +0530 Subject: [PATCH 28/85] Tools: create and use AP_PERIPH_RANGEFINDER_ENABLED --- Tools/AP_Periph/AP_Periph.cpp | 4 ++-- Tools/AP_Periph/AP_Periph.h | 4 ++-- Tools/AP_Periph/Parameters.cpp | 2 +- Tools/AP_Periph/Parameters.h | 2 +- Tools/AP_Periph/can.cpp | 4 ++-- Tools/AP_Periph/rangefinder.cpp | 4 ++-- Tools/AP_Periph/serial_tunnel.cpp | 2 +- Tools/ardupilotwaf/boards.py | 2 +- 8 files changed, 12 insertions(+), 12 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 4175c4d3deec19..d7bb3c69d7caf4 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -235,7 +235,7 @@ void AP_Periph_FW::init() #endif -#ifdef HAL_PERIPH_ENABLE_RANGEFINDER +#if AP_PERIPH_RANGEFINDER_ENABLED bool have_rangefinder = false; for (uint8_t i=0; i= 0)) { @@ -432,7 +432,7 @@ void AP_Periph_FW::update() #if AP_PERIPH_BARO_ENABLED 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 +#if AP_PERIPH_RANGEFINDER_ENABLED hal.serial(0)->printf("Num RNG sens %u\n", rangefinder.num_sensors()); for (uint8_t i=0; i Date: Fri, 24 Jan 2025 09:05:10 -0500 Subject: [PATCH 29/85] Reserving IDs for Lumenier. --- Tools/AP_Bootloader/board_types.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index edfb144e21637b..7136515e8897a4 100755 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -359,6 +359,9 @@ AP_HW_KRSHKF7_MINI 4000 AP_HW_HAKRC_F405 4200 AP_HW_HAKRC_F405Wing 4201 +# IDs 4500-4509 reserved for Lumenier +AP_HW_LUMENIER_LUX_F765_NDAA 4500 + # IDs 5000-5099 reserved for Carbonix # IDs 5100-5199 reserved for SYPAQ Systems # IDs 5200-5209 reserved for Airvolute From f6a6e356bf3c5966b309c8ce078183dd53ff4681 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 30 Jan 2025 18:20:56 +0000 Subject: [PATCH 30/85] AP_AIS: fix multi part message decoding --- libraries/AP_AIS/AP_AIS.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index 0523267ac587cc..7742745b6dc61a 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -146,21 +146,25 @@ void AP_AIS::update() } else if (_incoming.num == _incoming.total) { // last part of a multi part message uint8_t index = 0; - uint8_t msg_parts[_incoming.num - 1]; + + // We have the last part, need to find preceding fragments + const uint8_t parts = _incoming.num - 1; + + uint8_t msg_parts[parts]; for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) { // look for the rest of the message from the start of the buffer // we assume the message has be received in the correct order if (_AIVDM_buffer[i].num == (index + 1) && _AIVDM_buffer[i].total == _incoming.total && _AIVDM_buffer[i].ID == _incoming.ID) { msg_parts[index] = i; index++; - if (index >= _incoming.num) { + if (index >= parts) { break; } } } // did we find the right number? - if (_incoming.num != index) { + if (parts != index) { // could not find all of the message, save messages #if HAL_LOGGING_ENABLED if (log_unsupported) { @@ -180,14 +184,14 @@ void AP_AIS::update() // combine packets ExpandingString s; s.append(_AIVDM_buffer[msg_parts[0]].payload, strlen(_AIVDM_buffer[msg_parts[0]].payload)); - for (uint8_t i = 1; i < _incoming.total - 1; i++) { + for (uint8_t i = 1; i < index; i++) { s.append(_AIVDM_buffer[msg_parts[i]].payload, strlen(_AIVDM_buffer[msg_parts[i]].payload)); } s.append(_incoming.payload, strlen(_incoming.payload)); #if HAL_LOGGING_ENABLED const bool decoded = payload_decode(s.get_string()); #endif - for (uint8_t i = 0; i < _incoming.total; i++) { + for (uint8_t i = 0; i < index; i++) { #if HAL_LOGGING_ENABLED // unsupported type, log and discard if (!decoded && log_unsupported) { From 4ddd78e310f3928bc63d4fb495703fe7f14f3141 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 2 Feb 2025 16:09:36 +0000 Subject: [PATCH 31/85] Plane: plane.h: remove unused definitions --- ArduPlane/Plane.h | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 1de9159b455389..ebf773c2099f71 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -347,10 +347,6 @@ class Plane : public AP_Vehicle { // time of last mode change uint32_t last_mode_change_ms; - // Used to maintain the state of the previous control switch position - // This is set to 254 when we need to re-read the switch - uint8_t oldSwitchPosition = 254; - // This is used to enable the inverted flight feature bool inverted_flight; @@ -758,8 +754,6 @@ class Plane : public AP_Vehicle { // A starting value used to check the status of a conditional command. // For example in a delay command the condition_start records that start time for the delay uint32_t condition_start; - // A value used in condition commands. For example the rate at which to change altitude. - int16_t condition_rate; // 3D Location vectors // Location structure defined in AP_Common @@ -808,8 +802,6 @@ class Plane : public AP_Vehicle { float relative_altitude; - // loop performance monitoring: - AP::PerfInfo perf_info; struct { uint32_t last_trim_check; uint32_t last_trim_save; @@ -1042,13 +1034,10 @@ class Plane : public AP_Vehicle { bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; // control_modes.cpp - void read_control_switch(); - uint8_t readSwitch(void) const; void autotune_start(void); void autotune_restore(void); void autotune_enable(bool enable); bool fly_inverted(void); - bool mode_allows_autotuning(void); uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); } Mode *mode_from_mode_num(const enum Mode::Number num); bool current_mode_requires_mission() const override { @@ -1077,7 +1066,6 @@ class Plane : public AP_Vehicle { bool trigger_land_abort(const float climb_to_alt_m); void get_osd_roll_pitch_rad(float &roll, float &pitch) const override; float tecs_hgt_afe(void); - void efi_update(void); void get_scheduler_tasks(const AP_Scheduler::Task *&tasks, uint8_t &task_count, uint32_t &log_bit) override; @@ -1113,7 +1101,6 @@ class Plane : public AP_Vehicle { void calc_gndspeed_undershoot(); void update_loiter(uint16_t radius); void update_loiter_update_nav(uint16_t radius); - void update_cruise(); void update_fbwb_speed_height(void); void setup_turn_angle(void); bool reached_loiter_target(void); @@ -1168,7 +1155,6 @@ class Plane : public AP_Vehicle { float apply_throttle_limits(float throttle_in); void set_throttle(void); void set_takeoff_expected(void); - void set_servos_old_elevons(void); void set_servos_flaps(void); void set_landing_gear(void); void dspoiler_update(void); @@ -1196,7 +1182,6 @@ class Plane : public AP_Vehicle { // parachute.cpp void parachute_check(); #if HAL_PARACHUTE_ENABLED - void do_parachute(const AP_Mission::Mission_Command& cmd); void parachute_release(); bool parachute_manual_release(); #endif From 3e37b01e35a8758e58be64e1e52b674f2d7668b0 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 2 Feb 2025 16:09:56 +0000 Subject: [PATCH 32/85] Plane: remove unused method `set_target_altitude_current_adjusted` --- ArduPlane/Plane.h | 1 - ArduPlane/altitude.cpp | 11 ----------- 2 files changed, 12 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index ebf773c2099f71..86783bed8c1517 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -896,7 +896,6 @@ class Plane : public AP_Vehicle { float relative_ground_altitude(bool use_rangefinder_if_available); float relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available); void set_target_altitude_current(void); - void set_target_altitude_current_adjusted(void); void set_target_altitude_location(const Location &loc); int32_t relative_target_altitude_cm(void); void change_target_altitude(int32_t change_cm); diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index e96e778b82fa50..40219f26e6012f 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -208,17 +208,6 @@ void Plane::set_target_altitude_current(void) #endif } -/* - set the target altitude to the current altitude, with ALT_OFFSET adjustment - */ -void Plane::set_target_altitude_current_adjusted(void) -{ - set_target_altitude_current(); - - // use adjusted_altitude_cm() to take account of ALTITUDE_OFFSET - target_altitude.amsl_cm = adjusted_altitude_cm(); -} - /* set target altitude based on a location structure */ From e5efe490d9d566c5eab2627fe7a9e24e56c9828f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 2 Feb 2025 16:10:20 +0000 Subject: [PATCH 33/85] Plane: takeoff: use `tkoff_option_is_set` helper --- ArduPlane/takeoff.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 740daeaf057583..c07d9f293f52f0 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -285,7 +285,7 @@ void Plane::takeoff_calc_throttle() { const float current_baro_alt = barometer.get_altitude(); const bool below_lvl_alt = current_baro_alt < auto_state.baro_takeoff_alt + mode_takeoff.level_alt; // Set the minimum throttle limit. - const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE); + const bool use_throttle_range = tkoff_option_is_set(AP_FixedWing::TakeoffOption::THROTTLE_RANGE); if (!use_throttle_range // We don't want to employ a throttle range. || !ahrs.using_airspeed_sensor() // We don't have an airspeed sensor. || below_lvl_alt // We are below TKOFF_LVL_ALT. From 7667a04e03a49c89f523b976c7f9fc8256531c58 Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Mon, 23 Sep 2024 08:53:53 -0700 Subject: [PATCH 34/85] Sub: remove dead variable --- ArduSub/Attitude.cpp | 12 +++--------- ArduSub/Sub.h | 3 --- ArduSub/mode_surface.cpp | 3 --- 3 files changed, 3 insertions(+), 15 deletions(-) diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index de41b8833ec011..5a8ff5938db30e 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -94,7 +94,6 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) return 0.0f; } - float desired_rate = 0.0f; float mid_stick = channel_throttle->get_control_mid(); float deadband_top = mid_stick + g.throttle_deadzone * gain; float deadband_bottom = mid_stick - g.throttle_deadzone * gain; @@ -108,19 +107,14 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) // check throttle is above, below or in the deadband if (throttle_control < deadband_bottom) { // below the deadband - desired_rate = get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom; + return get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom; } else if (throttle_control > deadband_top) { // above the deadband - desired_rate = g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top); + return g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top); } else { // must be in the deadband - desired_rate = 0.0f; + return 0.0f; } - - // desired climb rate for logging - desired_climb_rate = desired_rate; - - return desired_rate; } // rotate vector from vehicle's perspective to North-East frame diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index bdf70e40d3fc11..db09827d994c09 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -263,9 +263,6 @@ class Sub : public AP_Vehicle { // Stores initial bearing when armed int32_t initial_armed_bearing; - // Throttle variables - int16_t desired_climb_rate; // pilot desired climb rate - for logging purposes only - // Loiter control uint16_t loiter_time_max; // How long we should stay in Loiter Mode for mission scripting (time in seconds) uint32_t loiter_time; // How long have we been loitering - The start time in millis diff --git a/ArduSub/mode_surface.cpp b/ArduSub/mode_surface.cpp index 6bab07a067b860..f554715076d227 100644 --- a/ArduSub/mode_surface.cpp +++ b/ArduSub/mode_surface.cpp @@ -50,9 +50,6 @@ void ModeSurface::run() // set target climb rate float cmb_rate = constrain_float(fabsf(sub.wp_nav.get_default_speed_up()), 1, position_control->get_max_speed_up_cms()); - // record desired climb rate for logging - sub.desired_climb_rate = cmb_rate; - // update altitude target and call position controller position_control->set_pos_target_z_from_climb_rate_cm(cmb_rate); position_control->update_z_controller(); From 025df2550ac03ba9155f67cf5ccfbde76e0e2120 Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Mon, 23 Sep 2024 08:54:21 -0700 Subject: [PATCH 35/85] Sub: poshold requires GPS --- ArduSub/mode.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduSub/mode.h b/ArduSub/mode.h index 9907ee95b46b84..ba1ba46d95c32b 100644 --- a/ArduSub/mode.h +++ b/ArduSub/mode.h @@ -420,7 +420,7 @@ class ModePoshold : public ModeAlthold bool init(bool ignore_checks) override; - bool requires_GPS() const override { return false; } + bool requires_GPS() const override { return true; } bool has_manual_throttle() const override { return false; } bool allows_arming(bool from_gcs) const override { return true; } bool is_autopilot() const override { return true; } From 2a28b77ef671369cadfb6c94239debb00abcbb0e Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Sat, 7 Dec 2024 09:35:31 -0800 Subject: [PATCH 36/85] Sub: limit poshold xy velocity to PILOT_SPEED to avoid bounceback --- ArduSub/Attitude.cpp | 27 ++++++++++++++++ ArduSub/Parameters.cpp | 9 ++++++ ArduSub/Parameters.h | 8 +++-- ArduSub/Sub.h | 1 + ArduSub/config.h | 5 ++- ArduSub/mode.h | 4 +++ ArduSub/mode_poshold.cpp | 67 ++++++++++++++++++++++++++-------------- 7 files changed, 93 insertions(+), 28 deletions(-) diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index 5a8ff5938db30e..dc0a9f4cd6da96 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -117,6 +117,33 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) } } +// behavior is similar to Sub::get_pilot_desired_climb_rate +float Sub::get_pilot_desired_horizontal_rate(RC_Channel *channel) const +{ + if (failsafe.pilot_input) { + return 0; + } + + // forward and lateral sticks have center trim, unlike throttle + auto control = channel->norm_input(); + + // normalize deadzone + auto dz = (float)g.throttle_deadzone * 2.0f / (float)(channel->get_radio_max() - channel->get_radio_min()); + auto deadband_top = dz * gain; + auto deadband_bottom = -dz * gain; + + if (control < deadband_bottom) { + // below the deadband + return (float)g.pilot_speed * (control - deadband_bottom); + } else if (control > deadband_top) { + // above the deadband + return (float)g.pilot_speed * (control - deadband_top); + } else { + // must be in the deadband + return 0; + } +} + // rotate vector from vehicle's perspective to North-East frame void Sub::rotate_body_frame_to_NE(float &x, float &y) { diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index b31f77cf794277..f16b3cb212a64d 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -175,6 +175,15 @@ const AP_Param::Info Sub::var_info[] = { // @User: Standard GSCALAR(pilot_speed_dn, "PILOT_SPEED_DN", 0), + // @Param: PILOT_SPEED + // @DisplayName: Pilot maximum horizontal speed + // @Description: The maximum horizontal velocity the pilot may request in cm/s + // @Units: cm/s + // @Range: 10 500 + // @Increment: 10 + // @User: Standard + GSCALAR(pilot_speed, "PILOT_SPEED", PILOT_SPEED_DEFAULT), + // @Param: PILOT_ACCEL_Z // @DisplayName: Pilot vertical acceleration // @Description: The vertical acceleration used when pilot is controlling the altitude diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index fe176e400e6c97..e7a9937260e282 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -231,6 +231,7 @@ class Parameters { k_param_pilot_speed_dn, k_param_rangefinder_signal_min, k_param_surftrak_depth, + k_param_pilot_speed, k_param_vehicle = 257, // vehicle common block of parameters }; @@ -267,9 +268,10 @@ class Parameters { // Waypoints // - AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request - AP_Int16 pilot_speed_dn; // maximum vertical descending velocity the pilot may request - AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request + AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request + AP_Int16 pilot_speed_dn; // maximum vertical descending velocity the pilot may request + AP_Int16 pilot_speed; // maximum horizontal (xy) velocity the pilot may request + AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request // Throttle // diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index db09827d994c09..0eca1a523f2a9e 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -403,6 +403,7 @@ class Sub : public AP_Vehicle { float get_roi_yaw(); float get_look_ahead_yaw(); float get_pilot_desired_climb_rate(float throttle_control); + float get_pilot_desired_horizontal_rate(RC_Channel *channel) const; void rotate_body_frame_to_NE(float &x, float &y); #if HAL_LOGGING_ENABLED // methods for AP_Vehicle: diff --git a/ArduSub/config.h b/ArduSub/config.h index 7e2f5686266e33..b45c38534697fc 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -167,10 +167,13 @@ # define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter #endif -// default maximum vertical velocity and acceleration the pilot may request +// default maximum velocities and acceleration the pilot may request #ifndef PILOT_VELZ_MAX # define PILOT_VELZ_MAX 500 // maximum vertical velocity in cm/s #endif +#ifndef PILOT_SPEED_DEFAULT +# define PILOT_SPEED_DEFAULT 200 // maximum horizontal velocity in cm/s while under pilot control +#endif #ifndef PILOT_ACCEL_Z_DEFAULT # define PILOT_ACCEL_Z_DEFAULT 100 // vertical acceleration in cm/s/s while altitude is under pilot control #endif diff --git a/ArduSub/mode.h b/ArduSub/mode.h index ba1ba46d95c32b..6bd47d55f37357 100644 --- a/ArduSub/mode.h +++ b/ArduSub/mode.h @@ -430,6 +430,10 @@ class ModePoshold : public ModeAlthold const char *name() const override { return "POSHOLD"; } const char *name4() const override { return "POSH"; } Mode::Number number() const override { return Mode::Number::POSHOLD; } + +private: + + void control_horizontal(); }; diff --git a/ArduSub/mode_poshold.cpp b/ArduSub/mode_poshold.cpp index 479cdcb5435b6a..559aa87f63296c 100644 --- a/ArduSub/mode_poshold.cpp +++ b/ArduSub/mode_poshold.cpp @@ -15,8 +15,8 @@ bool ModePoshold::init(bool ignore_checks) } // initialize vertical speeds and acceleration - position_control->set_max_speed_accel_xy(sub.wp_nav.get_default_speed_xy(), sub.wp_nav.get_wp_acceleration()); - position_control->set_correction_speed_accel_xy(sub.wp_nav.get_default_speed_xy(), sub.wp_nav.get_wp_acceleration()); + position_control->set_max_speed_accel_xy(g.pilot_speed, g.pilot_accel_z); + position_control->set_correction_speed_accel_xy(g.pilot_speed, g.pilot_accel_z); position_control->set_max_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); position_control->set_correction_speed_accel_z(-sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); @@ -54,26 +54,6 @@ void ModePoshold::run() // set motors to full range motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - /////////////////////// - // update xy outputs // - float pilot_lateral = channel_lateral->norm_input(); - float pilot_forward = channel_forward->norm_input(); - - float lateral_out = 0; - float forward_out = 0; - - if (sub.position_ok()) { - // Allow pilot to reposition the sub - if (fabsf(pilot_lateral) > 0.1 || fabsf(pilot_forward) > 0.1) { - position_control->init_xy_controller_stopping_point(); - } - sub.translate_pos_control_rp(lateral_out, forward_out); - position_control->update_xy_controller(); - } else { - position_control->init_xy_controller_stopping_point(); - } - motors.set_forward(forward_out + pilot_forward); - motors.set_lateral(lateral_out + pilot_lateral); ///////////////////// // Update attitude // @@ -103,12 +83,51 @@ void ModePoshold::run() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); sub.last_pilot_heading = ahrs.yaw_sensor; // update heading to hold - } else { // call attitude controller holding absolute absolute bearing + } else { // call attitude controller holding absolute bearing attitude_control->input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, sub.last_pilot_heading, true); } } - // Update z axis // + // update z axis control_depth(); + + // update xy axis + // call this after Sub::get_pilot_desired_climb_rate is called so that THR_DZ is reasonable + control_horizontal(); +} + +void ModePoshold::control_horizontal() { + float lateral_out = 0; + float forward_out = 0; + + // get desired rates in the body frame + Vector2f body_rates_cm_s = { + sub.get_pilot_desired_horizontal_rate(channel_forward), + sub.get_pilot_desired_horizontal_rate(channel_lateral) + }; + + if (sub.position_ok()) { + if (!position_control->is_active_xy()) { + // the xy controller timed out, re-initialize + position_control->init_xy_controller_stopping_point(); + } + + // convert to the earth frame and set target rates + auto earth_rates_cm_s = ahrs.body_to_earth2D(body_rates_cm_s); + position_control->input_vel_accel_xy(earth_rates_cm_s, {0, 0}); + + // convert pos control roll and pitch angles back to lateral and forward efforts + sub.translate_pos_control_rp(lateral_out, forward_out); + + // udpate the xy controller + position_control->update_xy_controller(); + } else if (g.pilot_speed > 0) { + // allow the pilot to reposition manually + forward_out = body_rates_cm_s.x / (float)g.pilot_speed; + lateral_out = body_rates_cm_s.y / (float)g.pilot_speed; + } + + motors.set_forward(forward_out); + motors.set_lateral(lateral_out); } #endif // POSHOLD_ENABLED From 1df67446f6c48c6bc56df78fd361949d5864fac1 Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Sat, 7 Dec 2024 09:35:49 -0800 Subject: [PATCH 37/85] autotest: test poshold bounceback --- Tools/autotest/ardusub.py | 56 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 88b498721f6c82..eb8078af774f60 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -992,6 +992,61 @@ def INA3221(self): }, epsilon=10) # allow rounding seen_3 = True + def wait_for_stop(self): + """Watch the sub slow down and stop""" + tstart = self.get_sim_time_cached() + lstart = self.mav.location() + + dmax = 0 + dprev = 0 + + while True: + self.delay_sim_time(1) + + dcurr = self.get_distance(lstart, self.mav.location()) + + if dcurr - dmax < -0.2: + raise NotAchievedException("Bounced back from %.2fm to %.2fm" % (dmax, dcurr)) + if dcurr > dmax: + dmax = dcurr + + if abs(dcurr - dprev) < 0.1: + self.progress("Stopping distance %.2fm, less than %.2fs" % (dcurr, self.get_sim_time_cached() - tstart)) + return + + if self.get_sim_time_cached() - tstart > 10: + raise NotAchievedException("Took to long to stop") + + dprev = dcurr + + def PosHoldBounceBack(self): + """Test for bounce back in POSHOLD mode""" + self.wait_ready_to_arm() + self.arm_vehicle() + + # dive a little + self.set_rc(Joystick.Throttle, 1300) + self.delay_sim_time(3) + self.set_rc(Joystick.Throttle, 1500) + self.delay_sim_time(2) + + # hold position + self.change_mode('POSHOLD') + + for pilot_speed in range(50, 251, 100): + # set max speed + self.set_parameter('PILOT_SPEED', pilot_speed) + + # try different stick values, resulting speed is ~ max_speed * effort * gain + for pwm in range(1700, 1901, 100): + self.progress('PILOT_SPEED %d, forward pwm %d' % (pilot_speed, pwm)) + self.set_rc(Joystick.Forward, pwm) + self.delay_sim_time(3) + self.set_rc(Joystick.Forward, 1500) + self.wait_for_stop() + + self.disarm_vehicle() + def tests(self): '''return list of all tests''' ret = super(AutoTestSub, self).tests() @@ -1024,6 +1079,7 @@ def tests(self): self.BackupOrigin, self.FuseMag, self.INA3221, + self.PosHoldBounceBack, ]) return ret From ab46ca2098657a41de21d0cb671b894d06ebd4b1 Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Mon, 25 Nov 2024 15:12:57 -0800 Subject: [PATCH 38/85] Sub: support MASK_LOG_IMU_FAST (loop rate logging) --- ArduSub/ArduSub.cpp | 11 ++++++++++- ArduSub/Sub.h | 1 + 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 002fbfbaad5915..e2923db562ff3c 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -91,6 +91,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { #if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350, 51), SCHED_TASK(twentyfive_hz_logging, 25, 110, 54), + SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 55), SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300, 57), #endif SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60), @@ -234,7 +235,15 @@ void Sub::twentyfive_hz_logging() } // log IMU data if we're not already logging at the higher rate - if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) { + if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_FAST)) { + AP::ins().Write_IMU(); + } +} + +// Full rate logging of IMU +void Sub::loop_rate_logging() +{ + if (should_log(MASK_LOG_IMU_FAST)) { AP::ins().Write_IMU(); } } diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 0eca1a523f2a9e..3e07fbf3ee405a 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -391,6 +391,7 @@ class Sub : public AP_Vehicle { void update_batt_compass(void); void ten_hz_logging_loop(); void twentyfive_hz_logging(); + void loop_rate_logging(); void three_hz_loop(); void one_hz_loop(); void update_turn_counter(); From a1421e7ece0ae7d224f1f1cabcb35152c0f6b42c Mon Sep 17 00:00:00 2001 From: ES-Alexander Date: Fri, 24 Jan 2025 18:35:57 +1100 Subject: [PATCH 39/85] AP_Baro: update MS5837_BA30 temperature compensation --- libraries/AP_Baro/AP_Baro_MS5611.cpp | 34 +++++++++++++++++----------- 1 file changed, 21 insertions(+), 13 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro_MS5611.cpp b/libraries/AP_Baro/AP_Baro_MS5611.cpp index 46e3d8d2c39f0d..533eb44ea7734f 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.cpp +++ b/libraries/AP_Baro/AP_Baro_MS5611.cpp @@ -486,29 +486,37 @@ void AP_Baro_MS56XX::_calculate_5637() // Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100). void AP_Baro_MS56XX::_calculate_5837() { - int32_t dT, TEMP; - int64_t OFF, SENS; + int32_t dT, TEMP, T2; + int64_t OFF, OFF2, SENS, SENS2; int32_t raw_pressure = _D1; int32_t raw_temperature = _D2; - // note that MS5837 has no compensation for temperatures below -15C in the datasheet - - dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8); + dT = raw_temperature - ((uint32_t)_cal_reg.c5 << 8); TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608; OFF = (int64_t)_cal_reg.c2 * (int64_t)65536 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)128; SENS = (int64_t)_cal_reg.c1 * (int64_t)32768 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)256; + int64_t aux = sq(TEMP - 2000); if (TEMP < 2000) { - // second order temperature compensation when under 20 degrees C - int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592); - int64_t aux = (TEMP - 2000) * (TEMP - 2000); - int64_t OFF2 = 3 * aux / 2; - int64_t SENS2 = 5 * aux / 8; + // second order "low temperature" compensation when under 20 degrees C + T2 = (int64_t)3 * sq((int64_t)dT) / (int64_t)8589934592; + OFF2 = 3 * aux / 2; + SENS2 = 5 * aux / 8; - TEMP = TEMP - T2; - OFF = OFF - OFF2; - SENS = SENS - SENS2; + if (TEMP < -1500) { + // "very low temperature" compensation, when under -15 degrees C + OFF2 += 7 * sq(TEMP+1500); + SENS2 += 4 * sq(TEMP+1500); + } + } else { + // "high temperature" compensation, when at or over 20 degrees C + T2 = (int64_t)2 * sq((int64_t)dT) / (int64_t)137438953472; + OFF2 = aux / 16; + SENS2 = 0; } + TEMP = TEMP - T2; + OFF = OFF - OFF2; + SENS = SENS - SENS2; int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)8192; pressure = pressure * 10; // MS5837 only reports to 0.1 mbar From e5e3e9a40bd966f8970060ae5465721813c8fc6e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Feb 2025 12:28:22 +1100 Subject: [PATCH 40/85] autotest: do not assert COMPASS_LEARN value after we set it the autopilot can instantly reset this back to 0 after we set it, so we never receive the set value: 2025-01-30T06:49:04.2029371Z AT-0931.7: COMPASS_LEARN want=3.000000 autopilot=0.0 (attempt=3/10) 2025-01-30T06:49:04.2029876Z AT-0931.7: Sending set (COMPASS_LEARN) to (3.000000) (old=0.000000) 2025-01-30T06:49:04.2030299Z AT-0931.7: AP: CompassLearn: Initialised 2025-01-30T06:49:04.2030653Z AT-0931.7: AP: CompassLearn: Finished 2025-01-30T06:49:04.2031166Z AT-0931.7: Received wanted PARAM_VALUE COMPASS_LEARN=0.000000 2025-01-30T06:49:04.2031653Z AT-0931.7: Received wanted PARAM_VALUE COMPASS_LEARN=3.000000 2025-01-30T06:49:04.2032117Z AT-0931.7: Received wanted PARAM_VALUE COMPASS_LEARN=0.000000 2025-01-30T06:49:04.2032732Z AT-0931.7: COMPASS_LEARN want=3.000000 autopilot=0.0 (attempt=4/10) --- Tools/autotest/arduplane.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 8c6721d8162e40..c3930ea4c61107 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -6460,7 +6460,7 @@ def CompassLearnInFlight(self): self.set_parameters({ "COMPASS_OFS_X": 1100, }) - self.set_parameter("COMPASS_LEARN", 3) # 3 is in-flight learning + self.send_set_parameter("COMPASS_LEARN", 3) # 3 is in-flight learning self.wait_parameter_value("COMPASS_LEARN", 0) self.assert_parameter_value("COMPASS_OFS_X", old_compass_ofs_x, epsilon=30) self.fly_home_land_and_disarm() From 9a1dc96a67006aaec663c814e73e38aa80eb1493 Mon Sep 17 00:00:00 2001 From: Wdiy Date: Sat, 1 Feb 2025 20:31:49 +0800 Subject: [PATCH 41/85] board_types.txt: add SULILGH7-P1-P2 --- Tools/AP_Bootloader/board_types.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 7136515e8897a4..c83fe967a3f501 100755 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -348,6 +348,8 @@ AP_HW_F4BY_F427 1530 AP_HW_MFT-SEMA100 2000 +AP_HW_SULILGH7-P1-P2 2005 + AP_HW_AET-H743-Basic 2024 AP_HW_SakuraRC-H743 2714 From 4db73d38831d88878f000135a3cdec3d0db756bc Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 16 Jan 2025 00:10:25 +0000 Subject: [PATCH 42/85] APM_Control: add test for roll and pitch controllers --- .../AP_FW_Controller_test.cpp | 299 ++++++++++++++++++ .../AP_FW_Controller_test/TestMatrix.sh | 47 +++ .../AP_FW_Controller_test/plot_results.py | 82 +++++ .../examples/AP_FW_Controller_test/wscript | 19 ++ 4 files changed, 447 insertions(+) create mode 100644 libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp create mode 100755 libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh create mode 100755 libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py create mode 100644 libraries/APM_Control/examples/AP_FW_Controller_test/wscript diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp b/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp new file mode 100644 index 00000000000000..09c39c8511592b --- /dev/null +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp @@ -0,0 +1,299 @@ +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +/* run with: + ./waf configure --board linux + ./waf build --targets examples/AP_FW_Controller_test + ./build/linux/examples/AP_FW_Controller_test +*/ + +void setup(); +void loop(); + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +// Need a scheduler so the controllers can get DT +AP_Scheduler scheduler; + +// When using stop clock the normal hal scheduler sleeps don't work. +// We need to sleep to clear print buffer, so microsleep implementation is copied here +void microsleep(uint32_t usec) +{ + struct timespec ts; + ts.tv_sec = 0; + ts.tv_nsec = usec*1000UL; + while (nanosleep(&ts, &ts) == -1 && errno == EINTR); +} + + +// Chirp object to generate test signal +Chirp chirp; + +// Chirp setup params +const float magnitude = 60.0; // deg - large magnitude means slew limit should kick in (very high values needed because of low default gains) +const float duration = 60.0; // seconds +const float frequency_start = 1.0; // hz +const float frequency_stop = 20; // hz, stay under the 25Hz nyquist limit on a 50Hz loop rate +const float time_fade_in = 15; // seconds +const float time_fade_out = 10; // seconds +const float time_const_freq = 2.0 / frequency_start; // seconds + +// Param object used by controllers +AP_FixedWing params; + +// Controller objects to test +AP_RollController roll_control { params }; +AP_PitchController pitch_control { params }; + +// 50 hz loop, start at time 0 +// Loop rate must match SCHEDULER_DEFAULT_LOOP_RATE +const uint16_t dt_us = 20000; +uint64_t waveform_time_us = 0; + +// Scaling speed parameter value +float scaling_speed = 15; + +// Default values for user provided configuration +enum class Axis { + Roll = 0, + Pitch = 1, +} test_axis = Axis::Roll; +bool override_have_airspeed = true; +float override_airspeed = 10; +float override_roll = 0; +float override_pitch = 0; +bool ground_mode = false; +bool disable_integrator = false; + +// Define the AHRS functions we need +AP_AHRS::AP_AHRS(uint8_t flags) : + _ekf_flags(flags) +{ + _singleton = this; +} + +// This is a dirty hack so we can set private values inside the ahrs +void AP_AHRS::update(bool skip_ins_update) +{ + roll = override_roll; + pitch = override_pitch; + update_cd_values(); + + state.airspeed = override_airspeed; + state.airspeed_ok = override_have_airspeed; +} + +// Copys of the functions we need out of AP_AHRS.cpp +bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const +{ + airspeed_ret = state.airspeed; + return state.airspeed_ok; +} +float AP_AHRS::get_EAS2TAS(void) const +{ + if (is_positive(state.EAS2TAS)) { + return state.EAS2TAS; + } + return 1.0; +} + +// singleton instance +AP_AHRS *AP_AHRS::_singleton; + +namespace AP { +AP_AHRS &ahrs() { + return *AP_AHRS::get_singleton(); +} +} + +AP_AHRS ahrs; + +// Calculate the airspeed scaler based on airspeed and the configured param +// Method from `Plane::calc_speed_scaler` +float calc_speed_scaler() +{ + float aspeed; + if (!ahrs.airspeed_estimate(aspeed)) { + return 1.0; + } + + // ensure we have scaling over the full configured airspeed + const float airspeed_min = MAX(params.airspeed_min, 5); + const float scale_min = MIN(0.5, scaling_speed / (2.0 * params.airspeed_max)); + const float scale_max = MAX(2.0, scaling_speed / (0.7 * airspeed_min)); + float speed_scaler = scale_max; + if (aspeed > 0.0001) { + speed_scaler = scaling_speed / aspeed; + } + return constrain_float(speed_scaler, scale_min, scale_max); +} + + +// setup function +void setup() +{ + // Read in user provided configuration + uint8_t argc; + char * const *argv; + hal.util->commandline_arguments(argc, argv); + if (argc > 1) { + for (uint8_t i = 1; i < argc; i++) { + const char *arg = argv[i]; + const char *eq = strchr(arg, '='); + + if (eq == NULL) { + ::printf("Expected argument with \"=\"\n"); + exit(1); + } + + char cmd[20] {}; + strncpy(cmd, arg, eq-arg); + const float value = atof(eq+1); + if (strcmp(cmd, "axis") == 0) { + if (strcmp(eq+1, "roll") == 0) { + test_axis = Axis::Roll; + } else if (strcmp(eq+1, "pitch") == 0) { + test_axis = Axis::Pitch; + + } else { + ::printf("Unknown axis: %s\n", eq+1); + exit(1); + } + + } else if (strcmp(cmd, "roll") == 0) { + override_roll = radians(value); + + } else if (strcmp(cmd, "pitch") == 0) { + override_pitch = radians(value); + + } else if (strcmp(cmd, "airspeed") == 0) { + override_airspeed = value; + + } else if (strcmp(cmd,"airspeed_fail") == 0) { + override_have_airspeed = value <= 0.0; + + } else if (strcmp(cmd,"ground_mode") == 0) { + ground_mode = value > 0.0; + + } else if (strcmp(cmd,"disable_integrator") == 0) { + disable_integrator = value > 0.0; + + } else { + ::printf("Expected \"axis\", \"roll\", \"pitch\", \"airspeed\", \"airspeed_fail\", \"ground_mode\", \"disable_integrator\"\n"); + exit(1); + } + } + } + + ::printf("FixedWing controller test - "); + switch (test_axis) { + case Axis::Roll: + ::printf("Roll"); + break; + + case Axis::Pitch: + ::printf("Pitch"); + break; + } + ::printf(" - ground_mode: %i, disable_integrator: %i\n", ground_mode, disable_integrator); + + // Set the configured values into the AHRS + ahrs.update(); + + // Set default values for the params used by the controllers + params.airspeed_min.set(9); + params.airspeed_max.set(22); + params.roll_limit.set(45); + params.pitch_limit_max.set(20); + params.pitch_limit_min.set(-25); + params.autotune_level.set(6); + params.autotune_options.set(0); + + // Setup chirp object + chirp.init(duration, frequency_start, frequency_stop, time_fade_in, time_fade_out, time_const_freq); + + // Force clock to start at 0 + hal.scheduler->stop_clock(waveform_time_us); + + // Print constant inputs + ::printf("Chirp - duration: %fs, magnitude: %f, start: %fHz, stop: %fHz, fade in: %fs, fade out:%fs, hold: %fs\n", duration, magnitude, frequency_start, frequency_stop, time_fade_in, time_fade_out, time_const_freq); + + // Print AHRS state + float airspeed = -1; + bool airspeed_ok = ahrs.airspeed_estimate(airspeed); + ::printf("AHRS - roll: %f, pitch: %f, airspeed: %f, airspeed OK: %i, EAS2TAS %f, gyro: { %f, %f, %f }\n", ahrs.roll_sensor * 0.01, ahrs.pitch_sensor * 0.01, airspeed, airspeed_ok, ahrs.get_EAS2TAS(), ahrs.get_gyro().x, ahrs.get_gyro().y, ahrs.get_gyro().z); + + // Header for results + ::printf("Time (s), angle error, output, PID target, PID actual, error, P, I, D, FF, DFF, Dmod, Slew rate, limit, PD limit, reset, I term set\n"); + +} + +void loop(void) +{ + // Update the chirp to generate input for controller + const float waveform_time_s = waveform_time_us * 1.0e-6; + const float nav_angle_cd = chirp.update(waveform_time_s, magnitude) * 100.0; + + // Calculate speed scaler + const float speed_scaler = calc_speed_scaler(); + + // Run the controller + float angle_error_cd; + float output; + const AP_PIDInfo* info = nullptr; + + switch (test_axis) { + case Axis::Roll: + angle_error_cd = nav_angle_cd - ahrs.roll_sensor; + output = roll_control.get_servo_out(angle_error_cd, speed_scaler, disable_integrator, ground_mode); + info = &roll_control.get_pid_info(); + break; + + case Axis::Pitch: + angle_error_cd = nav_angle_cd - ahrs.pitch_sensor; + output = pitch_control.get_servo_out(angle_error_cd, speed_scaler, disable_integrator, ground_mode); + info = &pitch_control.get_pid_info(); + break; + } + + // Print results + ::printf("%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%u,%u,%u,%u\n", + waveform_time_s, + angle_error_cd * 0.01, + output, + info->target, + info->actual, + info->error, + info->P, + info->I, + info->D, + info->FF, + info->DFF, + info->Dmod, + info->slew_rate, + info->limit, + info->PD_limit, + info->reset, + info->I_term_set); + + if (chirp.completed()) { + // Sleep gives the print buffer a chance to keep up + microsleep(10000); + exit(1); + } + + // Force clock times so we can run faster than real time + waveform_time_us += dt_us; + hal.scheduler->stop_clock(waveform_time_us); + +} + +AP_HAL_MAIN(); diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh b/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh new file mode 100755 index 00000000000000..35e06bffcfe703 --- /dev/null +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh @@ -0,0 +1,47 @@ +#!/usr/bin/env bash +# Fixedwing controller test and run over a range of inputs +# Output results to files for comparison + +cd "$(dirname "$0")" +cd ../../../.. + +mkdir -p FW_Controller_matrix + +./waf configure --board linux +./waf build --target examples/AP_FW_Controller_test +echo + +Axis="roll pitch" +Angle="-20 10 5 0 5 10 20" +Airspeed="5 10 15 20 25" + +COUNTER=0 +# Range of roll angles +for roll in $Angle; do + # Range of pitch angles + for pitch in $Angle; do + # Both roll and piith + for ax in $Axis; do + # Range of airspeeds + for speed in $Airspeed; do + ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch airspeed=$speed > FW_Controller_matrix/$COUNTER.csv + let COUNTER++ + done + + # Airspeed failure + ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch airspeed_fail=1 > FW_Controller_matrix/$COUNTER.csv + let COUNTER++ + + # Ground mode and intergrator diable flags, only test at defualt airspeed + ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch ground_mode=1 > FW_Controller_matrix/$COUNTER.csv + let COUNTER++ + + ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch disable_integrator=1 > FW_Controller_matrix/$COUNTER.csv + let COUNTER++ + + ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch ground_mode=1 disable_integrator=1 > FW_Controller_matrix/$COUNTER.csv + let COUNTER++ + done + done +done + diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py b/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py new file mode 100755 index 00000000000000..1993131259ec30 --- /dev/null +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py @@ -0,0 +1,82 @@ + +# Plot the results of a controller test run +# For example run test with: +# ./build/linux/examples/AP_FW_Controller_test > results.csv +# The plot with: +# python3 libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py results.csv + +import csv +from argparse import ArgumentParser +from collections import defaultdict +from matplotlib import pyplot as plt + +if __name__ == '__main__': + + parser = ArgumentParser(description='Plot results of controller test run') + parser.add_argument('filename', help='csv file to read') + args = parser.parse_args() + + with open(args.filename) as csv_file: + csv_reader = csv.DictReader(csv_file) + + # Skip First few lines + next(csv_file, None) + next(csv_file, None) + next(csv_file, None) + + csv_data = [row for row in csv_reader] + + # Reshape data from list of dicts to dict of lists + data = defaultdict(list) + for i in csv_data: + for key, value in i.items(): + data[key.strip()].append(float(value)) + + # Make some plots! + + fig, ax = plt.subplots(2) + fig.suptitle('Input => output') + ax[0].plot(data['Time (s)'], data['angle error']) + ax[0].set_ylabel('input angle error (deg)') + ax[1].plot(data['Time (s)'], data['output']) + ax[1].set_ylabel('output servo position') + ax[1].set_xlabel('Time (s)') + + fig, ax = plt.subplots(2) + fig.suptitle('Rate controller') + ax[0].plot(data['Time (s)'], data['PID target'], label = "target") + ax[0].plot(data['Time (s)'], data['PID actual'], label = "actual") + ax[0].legend() + ax[0].set_ylabel('rate target and actual') + ax[1].plot(data['Time (s)'], data['error']) + ax[1].set_ylabel('rate error') + ax[1].set_xlabel('Time (s)') + + fig = plt.figure() + plt.title('Rate controller PID components') + plt.plot(data['Time (s)'], data['P'], label = "P") + plt.plot(data['Time (s)'], data['I'], label = "I") + plt.plot(data['Time (s)'], data['D'], label = "D") + plt.plot(data['Time (s)'], data['FF'], label = "FF") + plt.plot(data['Time (s)'], data['DFF'], label = "DFF") + plt.legend() + plt.xlabel('Time (s)') + + fig, ax = plt.subplots(2) + fig.suptitle('Rate controller') + ax[0].plot(data['Time (s)'], data['Slew rate']) + ax[0].set_ylabel('Slew rate') + ax[1].plot(data['Time (s)'], data['Dmod']) + ax[1].set_ylabel('Dmod') + ax[1].set_xlabel('Time (s)') + + fig = plt.figure() + plt.title('Rate controller PID flags') + plt.plot(data['Time (s)'], data['limit'], label = "limit") + plt.plot(data['Time (s)'], data['PD limit'], label = "PD limit") + plt.plot(data['Time (s)'], data['reset'], label = "reset") + plt.plot(data['Time (s)'], data['I term set'], label = "I term set") + plt.legend() + plt.xlabel('Time (s)') + + plt.show() diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/wscript b/libraries/APM_Control/examples/AP_FW_Controller_test/wscript new file mode 100644 index 00000000000000..e1217655a46a70 --- /dev/null +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/wscript @@ -0,0 +1,19 @@ +#!/usr/bin/env python +# encoding: utf-8 + +def build(bld): + + if bld.env.BOARD != 'linux': + return + + # Turn off the normal AHRS so we can define a custom one + bld.env.DEFINES += ['AP_AHRS_ENABLED=0'] + + # Turn off other things that are expecting a complete AHRS + bld.env.DEFINES += ['AP_FRSKY_SPORT_PASSTHROUGH_ENABLED=0', 'AP_AIRSPEED_ENABLED=0'] + + bld.ap_program( + use='ap', + program_groups=['examples'], + ) + From f8dd0b2d763084164f47a5af1c99b62e87bc78a9 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 3 Aug 2024 19:33:22 +0100 Subject: [PATCH 43/85] APM_Control: add AP_FW_Controller as common base class to roll and pitch controllers --- libraries/APM_Control/AP_FW_Controller.cpp | 135 +++++++++++++++++++ libraries/APM_Control/AP_FW_Controller.h | 65 +++++++++ libraries/APM_Control/AP_PitchController.cpp | 132 ++++-------------- libraries/APM_Control/AP_PitchController.h | 61 ++------- libraries/APM_Control/AP_RollController.cpp | 125 ++++------------- libraries/APM_Control/AP_RollController.h | 60 +-------- 6 files changed, 266 insertions(+), 312 deletions(-) create mode 100644 libraries/APM_Control/AP_FW_Controller.cpp create mode 100644 libraries/APM_Control/AP_FW_Controller.h diff --git a/libraries/APM_Control/AP_FW_Controller.cpp b/libraries/APM_Control/AP_FW_Controller.cpp new file mode 100644 index 00000000000000..1aa6f64a51aeea --- /dev/null +++ b/libraries/APM_Control/AP_FW_Controller.cpp @@ -0,0 +1,135 @@ +/* + 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 . + */ +// Code by Jon Challinger +// Modified by Paul Riseborough +// + + +#include "AP_FW_Controller.h" +#include +#include + +AP_FW_Controller::AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults) + : aparm(parms), + rate_pid(defaults) +{ + rate_pid.set_slew_limit_scale(45); +} + +/* + AC_PID based rate controller +*/ +float AP_FW_Controller::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode) +{ + const float dt = AP::scheduler().get_loop_period_s(); + + const float eas2tas = AP::ahrs().get_EAS2TAS(); + bool limit_I = fabsf(_last_out) >= 45; + const float rate = get_measured_rate(); + const float old_I = rate_pid.get_i(); + + const bool underspeed = is_underspeed(aspeed); + if (underspeed) { + limit_I = true; + } + + // the P and I elements are scaled by sq(scaler). To use an + // unmodified AC_PID object we scale the inputs and calculate FF separately + // + // note that we run AC_PID in radians so that the normal scaling + // range for IMAX in AC_PID applies (usually an IMAX value less than 1.0) + rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate * scaler * scaler, dt, limit_I); + + if (underspeed) { + // when underspeed we lock the integrator + rate_pid.set_integrator(old_I); + } + + // FF should be scaled by scaler/eas2tas, but since we have scaled + // the AC_PID target above by scaler*scaler we need to instead + // divide by scaler*eas2tas to get the right scaling + const float ff = degrees(ff_scale * rate_pid.get_ff() / (scaler * eas2tas)); + ff_scale = 1.0; + + if (disable_integrator) { + rate_pid.reset_I(); + } + + // convert AC_PID info object to same scale as old controller + _pid_info = rate_pid.get_pid_info(); + auto &pinfo = _pid_info; + + const float deg_scale = degrees(1); + pinfo.FF = ff; + pinfo.P *= deg_scale; + pinfo.I *= deg_scale; + pinfo.D *= deg_scale; + pinfo.DFF *= deg_scale; + + // fix the logged target and actual values to not have the scalers applied + pinfo.target = desired_rate; + pinfo.actual = degrees(rate); + + // sum components + float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF; + if (ground_mode) { + // when on ground suppress D and half P term to prevent oscillations + out -= pinfo.D + 0.5*pinfo.P; + } + + // remember the last output to trigger the I limit + _last_out = out; + + if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) { + // let autotune have a go at the values + autotune->update(pinfo, scaler, angle_err_deg); + } + + // output is scaled to notional centidegrees of deflection + return constrain_float(out * 100, -4500, 4500); +} + +/* + Function returns an equivalent control surface deflection in centi-degrees in the range from -4500 to 4500 +*/ +float AP_FW_Controller::get_rate_out(float desired_rate, float scaler) +{ + return _get_rate_out(desired_rate, scaler, false, get_airspeed(), false); +} + +void AP_FW_Controller::reset_I() +{ + rate_pid.reset_I(); +} + +/* + reduce the integrator, used when we have a low scale factor in a quadplane hover +*/ +void AP_FW_Controller::decay_I() +{ + // this reduces integrator by 95% over 2s + _pid_info.I *= 0.995f; + rate_pid.set_integrator(rate_pid.get_i() * 0.995); +} + +/* + restore autotune gains + */ +void AP_FW_Controller::autotune_restore(void) +{ + if (autotune != nullptr) { + autotune->stop(); + } +} diff --git a/libraries/APM_Control/AP_FW_Controller.h b/libraries/APM_Control/AP_FW_Controller.h new file mode 100644 index 00000000000000..a552776215fd0b --- /dev/null +++ b/libraries/APM_Control/AP_FW_Controller.h @@ -0,0 +1,65 @@ +#pragma once + +#include +#include "AP_AutoTune.h" +#include + +class AP_FW_Controller +{ +public: + AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults); + + /* Do not allow copies */ + CLASS_NO_COPY(AP_FW_Controller); + + float get_rate_out(float desired_rate, float scaler); + virtual float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode) = 0; + + // setup a one loop FF scale multiplier. This replaces any previous scale applied + // so should only be used when only one source of scaling is needed + void set_ff_scale(float _ff_scale) { ff_scale = _ff_scale; } + + void reset_I(); + + /* + reduce the integrator, used when we have a low scale factor in a quadplane hover + */ + void decay_I(); + + virtual void autotune_start(void) = 0; + void autotune_restore(void); + + const AP_PIDInfo& get_pid_info(void) const + { + return _pid_info; + } + + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) { rate_pid.set_notch_sample_rate(sample_rate); } + + AP_Float &kP(void) { return rate_pid.kP(); } + AP_Float &kI(void) { return rate_pid.kI(); } + AP_Float &kD(void) { return rate_pid.kD(); } + AP_Float &kFF(void) { return rate_pid.ff(); } + AP_Float &tau(void) { return gains.tau; } + +protected: + const AP_FixedWing &aparm; + AP_AutoTune::ATGains gains; + AP_AutoTune *autotune; + bool failed_autotune_alloc; + float _last_out; + AC_PID rate_pid; + float angle_err_deg; + float ff_scale = 1.0; + + AP_PIDInfo _pid_info; + + float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode); + + virtual bool is_underspeed(const float aspeed) const = 0; + + virtual float get_airspeed() const = 0; + + virtual float get_measured_rate() const = 0; +}; diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 0bd2e9417e590b..071a3564e05954 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -162,105 +162,41 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = { }; AP_PitchController::AP_PitchController(const AP_FixedWing &parms) - : aparm(parms) + : AP_FW_Controller(parms, + AC_PID::Defaults{ + .p = 0.04, + .i = 0.15, + .d = 0.0, + .ff = 0.345, + .imax = 0.666, + .filt_T_hz = 3.0, + .filt_E_hz = 0.0, + .filt_D_hz = 12.0, + .srmax = 150.0, + .srtau = 1.0 + }) { AP_Param::setup_object_defaults(this, var_info); - rate_pid.set_slew_limit_scale(45); } -/* - AC_PID based rate controller -*/ -float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode) +float AP_PitchController::get_measured_rate() const { - const float dt = AP::scheduler().get_loop_period_s(); - - const AP_AHRS &_ahrs = AP::ahrs(); - - const float eas2tas = _ahrs.get_EAS2TAS(); - bool limit_I = fabsf(_last_out) >= 45; - float rate_y = _ahrs.get_gyro().y; - float old_I = rate_pid.get_i(); - - bool underspeed = aspeed <= 0.5*float(aparm.airspeed_min); - if (underspeed) { - limit_I = true; - } - - // the P and I elements are scaled by sq(scaler). To use an - // unmodified AC_PID object we scale the inputs and calculate FF separately - // - // note that we run AC_PID in radians so that the normal scaling - // range for IMAX in AC_PID applies (usually an IMAX value less than 1.0) - rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_y * scaler * scaler, dt, limit_I); - - if (underspeed) { - // when underspeed we lock the integrator - rate_pid.set_integrator(old_I); - } - - // FF should be scaled by scaler/eas2tas, but since we have scaled - // the AC_PID target above by scaler*scaler we need to instead - // divide by scaler*eas2tas to get the right scaling - const float ff = degrees(ff_scale * rate_pid.get_ff() / (scaler * eas2tas)); - ff_scale = 1.0; - - if (disable_integrator) { - rate_pid.reset_I(); - } - - // convert AC_PID info object to same scale as old controller - _pid_info = rate_pid.get_pid_info(); - auto &pinfo = _pid_info; - - const float deg_scale = degrees(1); - pinfo.FF = ff; - pinfo.P *= deg_scale; - pinfo.I *= deg_scale; - pinfo.D *= deg_scale; - pinfo.DFF *= deg_scale; - - // fix the logged target and actual values to not have the scalers applied - pinfo.target = desired_rate; - pinfo.actual = degrees(rate_y); - - // sum components - float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF; - if (ground_mode) { - // when on ground suppress D and half P term to prevent oscillations - out -= pinfo.D + 0.5*pinfo.P; - } - - // remember the last output to trigger the I limit - _last_out = out; - - if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) { - // let autotune have a go at the values - autotune->update(pinfo, scaler, angle_err_deg); - } - - // output is scaled to notional centidegrees of deflection - return constrain_float(out * 100, -4500, 4500); + return AP::ahrs().get_gyro().y; } -/* - Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500 - A positive demand is up - Inputs are: - 1) demanded pitch rate in degrees/second - 2) control gain scaler = scaling_speed / aspeed - 3) boolean which is true when stabilise mode is active - 4) minimum FBW airspeed (metres/sec) - 5) maximum FBW airspeed (metres/sec) -*/ -float AP_PitchController::get_rate_out(float desired_rate, float scaler) +float AP_PitchController::get_airspeed() const { float aspeed; if (!AP::ahrs().airspeed_estimate(aspeed)) { // If no airspeed available use average of min and max aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max)); } - return _get_rate_out(desired_rate, scaler, false, aspeed, false); + return aspeed; +} + +bool AP_PitchController::is_underspeed(const float aspeed) const +{ + return aspeed <= 0.5*float(aparm.airspeed_min); } /* @@ -270,7 +206,7 @@ float AP_PitchController::get_rate_out(float desired_rate, float scaler) Also returns the inverted flag and the estimated airspeed in m/s for use by the rest of the pitch controller */ -float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const +float AP_PitchController::_get_coordination_rate_offset(const float &aspeed, bool &inverted) const { float rate_offset; float bank_angle = AP::ahrs().get_roll(); @@ -288,10 +224,6 @@ float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inv } } const AP_AHRS &_ahrs = AP::ahrs(); - if (!_ahrs.airspeed_estimate(aspeed)) { - // If no airspeed available use average of min and max - aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max)); - } if (abs(_ahrs.pitch_sensor) > 7000) { // don't do turn coordination handling when at very high pitch angles rate_offset = 0; @@ -318,7 +250,6 @@ float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool di // Calculate offset to pitch rate demand required to maintain pitch angle whilst banking // Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn // Pitch rate offset is the component of turn rate about the pitch axis - float aspeed; float rate_offset; bool inverted; @@ -326,6 +257,8 @@ float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool di gains.tau.set(0.05f); } + const float aspeed = get_airspeed(); + rate_offset = _get_coordination_rate_offset(aspeed, inverted); // Calculate the desired pitch rate (deg/sec) from the angle error @@ -370,11 +303,6 @@ float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool di return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed, ground_mode); } -void AP_PitchController::reset_I() -{ - rate_pid.reset_I(); -} - /* convert from old to new PIDs this is a temporary conversion function during development @@ -424,13 +352,3 @@ void AP_PitchController::autotune_start(void) autotune->start(); } } - -/* - restore autotune gains - */ -void AP_PitchController::autotune_restore(void) -{ - if (autotune != nullptr) { - autotune->stop(); - } -} diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index e2900d15ad11a4..48736e7421d435 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -1,11 +1,8 @@ #pragma once -#include -#include "AP_AutoTune.h" -#include -#include +#include "AP_FW_Controller.h" -class AP_PitchController +class AP_PitchController : public AP_FW_Controller { public: AP_PitchController(const AP_FixedWing &parms); @@ -13,60 +10,20 @@ class AP_PitchController /* Do not allow copies */ CLASS_NO_COPY(AP_PitchController); - float get_rate_out(float desired_rate, float scaler); - float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode); - - // setup a one loop FF scale multiplier. This replaces any previous scale applied - // so should only be used when only one source of scaling is needed - void set_ff_scale(float _ff_scale) { ff_scale = _ff_scale; } - - void reset_I(); - - /* - reduce the integrator, used when we have a low scale factor in a quadplane hover - */ - void decay_I() - { - // this reduces integrator by 95% over 2s - _pid_info.I *= 0.995f; - rate_pid.set_integrator(rate_pid.get_i() * 0.995); - } - - void autotune_start(void); - void autotune_restore(void); - - const AP_PIDInfo& get_pid_info(void) const - { - return _pid_info; - } - - // set the PID notch sample rates - void set_notch_sample_rate(float sample_rate) { rate_pid.set_notch_sample_rate(sample_rate); } + float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode) override; + void autotune_start(void) override; static const struct AP_Param::GroupInfo var_info[]; - AP_Float &kP(void) { return rate_pid.kP(); } - AP_Float &kI(void) { return rate_pid.kI(); } - AP_Float &kD(void) { return rate_pid.kD(); } - AP_Float &kFF(void) { return rate_pid.ff(); } - AP_Float &tau(void) { return gains.tau; } - void convert_pid(); private: - const AP_FixedWing &aparm; - AP_AutoTune::ATGains gains; - AP_AutoTune *autotune; - bool failed_autotune_alloc; - AP_Int16 _max_rate_neg; AP_Float _roll_ff; - float _last_out; - AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 3, 0, 12, 150, 1}; - float angle_err_deg; - float ff_scale = 1.0; - AP_PIDInfo _pid_info; + float _get_coordination_rate_offset(const float &aspeed, bool &inverted) const; + + float get_airspeed() const override; + bool is_underspeed(const float aspeed) const override; + float get_measured_rate() const override; - float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode); - float _get_coordination_rate_offset(float &aspeed, bool &inverted) const; }; diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 6f16fd2b0245db..3766fb79f77fb4 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -146,101 +146,41 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { // constructor AP_RollController::AP_RollController(const AP_FixedWing &parms) - : aparm(parms) + : AP_FW_Controller(parms, + AC_PID::Defaults{ + .p = 0.08, + .i = 0.15, + .d = 0.0, + .ff = 0.345, + .imax = 0.666, + .filt_T_hz = 3.0, + .filt_E_hz = 0.0, + .filt_D_hz = 12.0, + .srmax = 150.0, + .srtau = 1.0 + }) { AP_Param::setup_object_defaults(this, var_info); - rate_pid.set_slew_limit_scale(45); } - -/* - AC_PID based rate controller -*/ -float AP_RollController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, bool ground_mode) +float AP_RollController::get_measured_rate() const { - const AP_AHRS &_ahrs = AP::ahrs(); + return AP::ahrs().get_gyro().x; +} - const float dt = AP::scheduler().get_loop_period_s(); - const float eas2tas = _ahrs.get_EAS2TAS(); - bool limit_I = fabsf(_last_out) >= 45; - float rate_x = _ahrs.get_gyro().x; +float AP_RollController::get_airspeed() const +{ float aspeed; - float old_I = rate_pid.get_i(); - - if (!_ahrs.airspeed_estimate(aspeed)) { - aspeed = 0; - } - bool underspeed = aspeed <= float(aparm.airspeed_min); - if (underspeed) { - limit_I = true; - } - - // the P and I elements are scaled by sq(scaler). To use an - // unmodified AC_PID object we scale the inputs and calculate FF separately - // - // note that we run AC_PID in radians so that the normal scaling - // range for IMAX in AC_PID applies (usually an IMAX value less than 1.0) - rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_x * scaler * scaler, dt, limit_I); - - if (underspeed) { - // when underspeed we lock the integrator - rate_pid.set_integrator(old_I); - } - - // FF should be scaled by scaler/eas2tas, but since we have scaled - // the AC_PID target above by scaler*scaler we need to instead - // divide by scaler*eas2tas to get the right scaling - const float ff = degrees(ff_scale * rate_pid.get_ff() / (scaler * eas2tas)); - ff_scale = 1.0; - - if (disable_integrator) { - rate_pid.reset_I(); - } - - // convert AC_PID info object to same scale as old controller - _pid_info = rate_pid.get_pid_info(); - auto &pinfo = _pid_info; - - const float deg_scale = degrees(1); - pinfo.FF = ff; - pinfo.P *= deg_scale; - pinfo.I *= deg_scale; - pinfo.D *= deg_scale; - pinfo.DFF *= deg_scale; - - // fix the logged target and actual values to not have the scalers applied - pinfo.target = desired_rate; - pinfo.actual = degrees(rate_x); - - // sum components - float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF; - if (ground_mode) { - // when on ground suppress D term to prevent oscillations - out -= pinfo.D + 0.5*pinfo.P; - } - - // remember the last output to trigger the I limit - _last_out = out; - - if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) { - // let autotune have a go at the values - autotune->update(pinfo, scaler, angle_err_deg); + if (!AP::ahrs().airspeed_estimate(aspeed)) { + // If no airspeed available use 0 + aspeed = 0.0; } - - // output is scaled to notional centidegrees of deflection - return constrain_float(out * 100, -4500, 4500); + return aspeed; } -/* - Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500 - A positive demand is up - Inputs are: - 1) desired roll rate in degrees/sec - 2) control gain scaler = scaling_speed / aspeed -*/ -float AP_RollController::get_rate_out(float desired_rate, float scaler) +bool AP_RollController::is_underspeed(const float aspeed) const { - return _get_rate_out(desired_rate, scaler, false, false); + return aspeed <= float(aparm.airspeed_min); } /* @@ -269,12 +209,7 @@ float AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool dis desired_rate = gains.rmax_pos; } - return _get_rate_out(desired_rate, scaler, disable_integrator, ground_mode); -} - -void AP_RollController::reset_I() -{ - rate_pid.reset_I(); + return _get_rate_out(desired_rate, scaler, disable_integrator, get_airspeed(), ground_mode); } /* @@ -325,13 +260,3 @@ void AP_RollController::autotune_start(void) autotune->start(); } } - -/* - restore autotune gains - */ -void AP_RollController::autotune_restore(void) -{ - if (autotune != nullptr) { - autotune->stop(); - } -} diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 35a8a331cc8305..aef4a933d6a8ae 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -1,11 +1,8 @@ #pragma once -#include -#include "AP_AutoTune.h" -#include -#include +#include "AP_FW_Controller.h" -class AP_RollController +class AP_RollController : public AP_FW_Controller { public: AP_RollController(const AP_FixedWing &parms); @@ -13,59 +10,16 @@ class AP_RollController /* Do not allow copies */ CLASS_NO_COPY(AP_RollController); - float get_rate_out(float desired_rate, float scaler); - float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode); + float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode) override; - // setup a one loop FF scale multiplier. This replaces any previous scale applied - // so should only be used when only one source of scaling is needed - void set_ff_scale(float _ff_scale) { ff_scale = _ff_scale; } - - void reset_I(); - - /* - reduce the integrator, used when we have a low scale factor in a quadplane hover - */ - void decay_I() - { - // this reduces integrator by 95% over 2s - _pid_info.I *= 0.995f; - rate_pid.set_integrator(rate_pid.get_i() * 0.995); - } - - void autotune_start(void); - void autotune_restore(void); - - const AP_PIDInfo& get_pid_info(void) const - { - return _pid_info; - } - - // set the PID notch sample rates - void set_notch_sample_rate(float sample_rate) { rate_pid.set_notch_sample_rate(sample_rate); } + void autotune_start(void) override; static const struct AP_Param::GroupInfo var_info[]; - - // tuning accessors - AP_Float &kP(void) { return rate_pid.kP(); } - AP_Float &kI(void) { return rate_pid.kI(); } - AP_Float &kD(void) { return rate_pid.kD(); } - AP_Float &kFF(void) { return rate_pid.ff(); } - AP_Float &tau(void) { return gains.tau; } - void convert_pid(); private: - const AP_FixedWing &aparm; - AP_AutoTune::ATGains gains; - AP_AutoTune *autotune; - bool failed_autotune_alloc; - float _last_out; - AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 3, 0, 12, 150, 1}; - float angle_err_deg; - float ff_scale = 1.0; - - AP_PIDInfo _pid_info; - - float _get_rate_out(float desired_rate, float scaler, bool disable_integrator, bool ground_mode); + float get_airspeed() const override; + bool is_underspeed(const float aspeed) const override; + float get_measured_rate() const override; }; From 790290d359a96496005b3606fff155757379952c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Nov 2024 13:59:59 +0000 Subject: [PATCH 44/85] APM_Control: AP_AutoTune: add static `axis_string` method --- libraries/APM_Control/AP_AutoTune.cpp | 7 ++++++- libraries/APM_Control/AP_AutoTune.h | 2 ++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 24a8611bacf58d..057669b7037317 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -153,7 +153,12 @@ void AP_AutoTune::stop(void) const char *AP_AutoTune::axis_string(void) const { - switch (type) { + return axis_string(type); +} + +const char *AP_AutoTune::axis_string(ATType _type) +{ + switch (_type) { case AUTOTUNE_ROLL: return "Roll"; case AUTOTUNE_PITCH: diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index a1312bc4c9d712..a4bdba06aa9a87 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -64,6 +64,8 @@ class AP_AutoTune // are we running? bool running; + static const char *axis_string(ATType _type); + private: // the current gains ATGains ¤t; From 44d2fc1ac1bf8b1f2b2338df128631958083621f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Nov 2024 14:00:47 +0000 Subject: [PATCH 45/85] AMP_Control: move pitch and roll `autotune_start` into base `AP_FW_Controller` --- libraries/APM_Control/AP_FW_Controller.cpp | 26 ++++++++++++++++++-- libraries/APM_Control/AP_FW_Controller.h | 6 +++-- libraries/APM_Control/AP_PitchController.cpp | 23 ++--------------- libraries/APM_Control/AP_PitchController.h | 1 - libraries/APM_Control/AP_RollController.cpp | 23 ++--------------- libraries/APM_Control/AP_RollController.h | 2 -- 6 files changed, 32 insertions(+), 49 deletions(-) diff --git a/libraries/APM_Control/AP_FW_Controller.cpp b/libraries/APM_Control/AP_FW_Controller.cpp index 1aa6f64a51aeea..22a51e75a787d4 100644 --- a/libraries/APM_Control/AP_FW_Controller.cpp +++ b/libraries/APM_Control/AP_FW_Controller.cpp @@ -20,10 +20,12 @@ #include "AP_FW_Controller.h" #include #include +#include -AP_FW_Controller::AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults) +AP_FW_Controller::AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults, AP_AutoTune::ATType _autotune_type) : aparm(parms), - rate_pid(defaults) + rate_pid(defaults), + autotune_type(_autotune_type) { rate_pid.set_slew_limit_scale(45); } @@ -133,3 +135,23 @@ void AP_FW_Controller::autotune_restore(void) autotune->stop(); } } + +/* + start an autotune + */ +void AP_FW_Controller::autotune_start(void) +{ + if (autotune == nullptr) { + autotune = NEW_NOTHROW AP_AutoTune(gains, autotune_type, aparm, rate_pid); + if (autotune == nullptr) { + if (!failed_autotune_alloc) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed %s allocation", AP_AutoTune::axis_string(autotune_type)); + } + failed_autotune_alloc = true; + } + } + if (autotune != nullptr) { + autotune->start(); + } +} + diff --git a/libraries/APM_Control/AP_FW_Controller.h b/libraries/APM_Control/AP_FW_Controller.h index a552776215fd0b..5cd81bdc412426 100644 --- a/libraries/APM_Control/AP_FW_Controller.h +++ b/libraries/APM_Control/AP_FW_Controller.h @@ -7,7 +7,7 @@ class AP_FW_Controller { public: - AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults); + AP_FW_Controller(const AP_FixedWing &parms, const AC_PID::Defaults &defaults, AP_AutoTune::ATType _autotune_type); /* Do not allow copies */ CLASS_NO_COPY(AP_FW_Controller); @@ -26,7 +26,7 @@ class AP_FW_Controller */ void decay_I(); - virtual void autotune_start(void) = 0; + void autotune_start(void); void autotune_restore(void); const AP_PIDInfo& get_pid_info(void) const @@ -62,4 +62,6 @@ class AP_FW_Controller virtual float get_airspeed() const = 0; virtual float get_measured_rate() const = 0; + + const AP_AutoTune::ATType autotune_type; }; diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 071a3564e05954..64908641d08fce 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -20,7 +20,6 @@ #include "AP_PitchController.h" #include #include -#include extern const AP_HAL::HAL& hal; @@ -174,7 +173,8 @@ AP_PitchController::AP_PitchController(const AP_FixedWing &parms) .filt_D_hz = 12.0, .srmax = 150.0, .srtau = 1.0 - }) + }, + AP_AutoTune::ATType::AUTOTUNE_PITCH) { AP_Param::setup_object_defaults(this, var_info); } @@ -333,22 +333,3 @@ void AP_PitchController::convert_pid() rate_pid.kD().set_and_save_ifchanged(0); rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0); } - -/* - start an autotune - */ -void AP_PitchController::autotune_start(void) -{ - if (autotune == nullptr) { - autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid); - if (autotune == nullptr) { - if (!failed_autotune_alloc) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed pitch allocation"); - } - failed_autotune_alloc = true; - } - } - if (autotune != nullptr) { - autotune->start(); - } -} diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index 48736e7421d435..1cef2b5ea9adf2 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -11,7 +11,6 @@ class AP_PitchController : public AP_FW_Controller CLASS_NO_COPY(AP_PitchController); float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode) override; - void autotune_start(void) override; static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 3766fb79f77fb4..3cf2f2f9781791 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -21,7 +21,6 @@ #include "AP_RollController.h" #include #include -#include extern const AP_HAL::HAL& hal; @@ -158,7 +157,8 @@ AP_RollController::AP_RollController(const AP_FixedWing &parms) .filt_D_hz = 12.0, .srmax = 150.0, .srtau = 1.0 - }) + }, + AP_AutoTune::ATType::AUTOTUNE_ROLL) { AP_Param::setup_object_defaults(this, var_info); } @@ -241,22 +241,3 @@ void AP_RollController::convert_pid() rate_pid.kD().set_and_save_ifchanged(0); rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0); } - -/* - start an autotune - */ -void AP_RollController::autotune_start(void) -{ - if (autotune == nullptr) { - autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_ROLL, aparm, rate_pid); - if (autotune == nullptr) { - if (!failed_autotune_alloc) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed roll allocation"); - } - failed_autotune_alloc = true; - } - } - if (autotune != nullptr) { - autotune->start(); - } -} diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index aef4a933d6a8ae..d625d3b533eb98 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -12,8 +12,6 @@ class AP_RollController : public AP_FW_Controller float get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode) override; - void autotune_start(void) override; - static const struct AP_Param::GroupInfo var_info[]; void convert_pid(); From 63fecc76d423e71fb7da2fc549fcc827c3c60aa5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 1 Feb 2025 16:01:52 +0000 Subject: [PATCH 46/85] APM_Control: examples: AP_FW_Controller_test: update to use HAL SITL --- .../AP_FW_Controller_test.cpp | 128 ++++++++++-------- .../AP_FW_Controller_test/TestMatrix.sh | 19 +-- .../AP_FW_Controller_test/plot_results.py | 5 + .../examples/AP_FW_Controller_test/wscript | 16 ++- 4 files changed, 95 insertions(+), 73 deletions(-) diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp b/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp index 09c39c8511592b..731b8c73a86c7a 100644 --- a/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/AP_FW_Controller_test.cpp @@ -1,28 +1,59 @@ #include +#include #include #include #include #include + +#include #include +#include +#include +#include +#include +#include +#include +#include + #include #include -#include + +#include /* run with: - ./waf configure --board linux + ./waf configure --board sitl ./waf build --targets examples/AP_FW_Controller_test - ./build/linux/examples/AP_FW_Controller_test + ./build/sitl/examples/AP_FW_Controller_test */ void setup(); void loop(); +void microsleep(uint32_t usec); +float calc_speed_scaler(); const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +// Sim backend allows us to inject values into the AHRS +SITL::SIM sim; + // Need a scheduler so the controllers can get DT AP_Scheduler scheduler; +// Controllers use AHRS, it also needs some supporting libs +AP_AHRS ahrs; +AP_InertialSensor ins; +Compass compass; +AP_GPS gps; +AP_Baro baro; +AP_ExternalAHRS ext_ahrs; +AP_Logger logger; + +const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { + AP_GROUPEND +}; +GCS_Dummy _gcs; + // When using stop clock the normal hal scheduler sleeps don't work. // We need to sleep to clear print buffer, so microsleep implementation is copied here void microsleep(uint32_t usec) @@ -65,57 +96,11 @@ float scaling_speed = 15; enum class Axis { Roll = 0, Pitch = 1, -} test_axis = Axis::Roll; -bool override_have_airspeed = true; -float override_airspeed = 10; -float override_roll = 0; -float override_pitch = 0; +}; +Axis test_axis = Axis::Roll; bool ground_mode = false; bool disable_integrator = false; -// Define the AHRS functions we need -AP_AHRS::AP_AHRS(uint8_t flags) : - _ekf_flags(flags) -{ - _singleton = this; -} - -// This is a dirty hack so we can set private values inside the ahrs -void AP_AHRS::update(bool skip_ins_update) -{ - roll = override_roll; - pitch = override_pitch; - update_cd_values(); - - state.airspeed = override_airspeed; - state.airspeed_ok = override_have_airspeed; -} - -// Copys of the functions we need out of AP_AHRS.cpp -bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const -{ - airspeed_ret = state.airspeed; - return state.airspeed_ok; -} -float AP_AHRS::get_EAS2TAS(void) const -{ - if (is_positive(state.EAS2TAS)) { - return state.EAS2TAS; - } - return 1.0; -} - -// singleton instance -AP_AHRS *AP_AHRS::_singleton; - -namespace AP { -AP_AHRS &ahrs() { - return *AP_AHRS::get_singleton(); -} -} - -AP_AHRS ahrs; - // Calculate the airspeed scaler based on airspeed and the configured param // Method from `Plane::calc_speed_scaler` float calc_speed_scaler() @@ -140,6 +125,12 @@ float calc_speed_scaler() // setup function void setup() { + // Default values for user provided configuration + bool override_have_airspeed = true; + float override_airspeed = 10; + float override_roll = 0; + float override_pitch = 0; + // Read in user provided configuration uint8_t argc; char * const *argv; @@ -193,6 +184,16 @@ void setup() } } + // Set the configured values into the AHRS + ahrs.set_ekf_type(AP_AHRS::EKFType::SIM); + sim.state.airspeed = override_airspeed; + ahrs.set_wind_estimation_enabled(override_have_airspeed); + sim.state.quaternion.from_euler(override_roll, override_pitch, 0.0); + ahrs.update(true); + + // Delay so GCS print clears + hal.scheduler->delay(1); + ::printf("FixedWing controller test - "); switch (test_axis) { case Axis::Roll: @@ -205,9 +206,6 @@ void setup() } ::printf(" - ground_mode: %i, disable_integrator: %i\n", ground_mode, disable_integrator); - // Set the configured values into the AHRS - ahrs.update(); - // Set default values for the params used by the controllers params.airspeed_min.set(9); params.airspeed_max.set(22); @@ -265,7 +263,7 @@ void loop(void) } // Print results - ::printf("%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%0.4f,%u,%u,%u,%u\n", + ::printf("%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%u,%u,%u,%u\n", waveform_time_s, angle_error_cd * 0.01, output, @@ -286,7 +284,7 @@ void loop(void) if (chirp.completed()) { // Sleep gives the print buffer a chance to keep up - microsleep(10000); + microsleep(100); exit(1); } @@ -294,6 +292,22 @@ void loop(void) waveform_time_us += dt_us; hal.scheduler->stop_clock(waveform_time_us); + microsleep(5); + } -AP_HAL_MAIN(); +AP_HAL::HAL::FunCallbacks callbacks(setup, loop); +extern "C" { + int AP_MAIN(int argc, char* const argv[]); + int AP_MAIN(int argc, char* const argv[]) { + + // Turn off Serial 1 because it blocks annoyingly + HAL_SITL& hal_sitl = (HAL_SITL&)AP_HAL::get_HAL_mutable(); + + // Duplicate string so it can be freed + hal_sitl.get_sitl_state()->_serial_path[0] = strdup("none"); + + hal.run(argc, argv, &callbacks); + return 0; + } +} diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh b/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh index 35e06bffcfe703..f41e44d9b57ce8 100755 --- a/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/TestMatrix.sh @@ -7,39 +7,40 @@ cd ../../../.. mkdir -p FW_Controller_matrix -./waf configure --board linux +./waf configure --board sitl ./waf build --target examples/AP_FW_Controller_test echo Axis="roll pitch" -Angle="-20 10 5 0 5 10 20" +RollAngle="-170 -160 -150 -140 -130 -120 -110 -100 -90 -80 -70 -60 -50 -40 -30 -20 10 0 10 20 30 40 50 60 70 80 90 100 110 120 130 140 150 160 170 180" +PitchAngle="-80 -70 -60 -50 -40 -30 -20 10 0 10 20 30 40 50 60 70 80" Airspeed="5 10 15 20 25" COUNTER=0 # Range of roll angles -for roll in $Angle; do +for roll in $RollAngle; do # Range of pitch angles - for pitch in $Angle; do + for pitch in $PitchAngle; do # Both roll and piith for ax in $Axis; do # Range of airspeeds for speed in $Airspeed; do - ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch airspeed=$speed > FW_Controller_matrix/$COUNTER.csv + ./build/sitl/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch airspeed=$speed > FW_Controller_matrix/$COUNTER.csv let COUNTER++ done # Airspeed failure - ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch airspeed_fail=1 > FW_Controller_matrix/$COUNTER.csv + ./build/sitl/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch airspeed_fail=1 > FW_Controller_matrix/$COUNTER.csv let COUNTER++ # Ground mode and intergrator diable flags, only test at defualt airspeed - ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch ground_mode=1 > FW_Controller_matrix/$COUNTER.csv + ./build/sitl/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch ground_mode=1 > FW_Controller_matrix/$COUNTER.csv let COUNTER++ - ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch disable_integrator=1 > FW_Controller_matrix/$COUNTER.csv + ./build/sitl/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch disable_integrator=1 > FW_Controller_matrix/$COUNTER.csv let COUNTER++ - ./build/linux/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch ground_mode=1 disable_integrator=1 > FW_Controller_matrix/$COUNTER.csv + ./build/sitl/examples/AP_FW_Controller_test axis=$ax roll=$roll pitch=$pitch ground_mode=1 disable_integrator=1 > FW_Controller_matrix/$COUNTER.csv let COUNTER++ done done diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py b/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py index 1993131259ec30..66399c23b52c22 100755 --- a/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/plot_results.py @@ -23,6 +23,11 @@ next(csv_file, None) next(csv_file, None) next(csv_file, None) + next(csv_file, None) + next(csv_file, None) + next(csv_file, None) + next(csv_file, None) + next(csv_file, None) csv_data = [row for row in csv_reader] diff --git a/libraries/APM_Control/examples/AP_FW_Controller_test/wscript b/libraries/APM_Control/examples/AP_FW_Controller_test/wscript index e1217655a46a70..613b2494a61717 100644 --- a/libraries/APM_Control/examples/AP_FW_Controller_test/wscript +++ b/libraries/APM_Control/examples/AP_FW_Controller_test/wscript @@ -3,17 +3,19 @@ def build(bld): - if bld.env.BOARD != 'linux': + if bld.env.BOARD != 'sitl': return - # Turn off the normal AHRS so we can define a custom one - bld.env.DEFINES += ['AP_AHRS_ENABLED=0'] - - # Turn off other things that are expecting a complete AHRS - bld.env.DEFINES += ['AP_FRSKY_SPORT_PASSTHROUGH_ENABLED=0', 'AP_AIRSPEED_ENABLED=0'] + bld.ap_stlib( + name='AP_FW_Controller_test_libs', + ap_vehicle='UNKNOWN', + ap_libraries=bld.ap_common_vehicle_libraries() + [ + 'SITL', 'APM_Control', 'AP_AdvancedFailsafe', + ], + ) bld.ap_program( - use='ap', + use='AP_FW_Controller_test_libs', program_groups=['examples'], ) From 022c43c644101e1e1aea237e10cdb230b420fdb5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 1 Feb 2025 16:02:18 +0000 Subject: [PATCH 47/85] AP_HAL_SITL: Add getter for `SITL_State` --- libraries/AP_HAL_SITL/HAL_SITL_Class.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.h b/libraries/AP_HAL_SITL/HAL_SITL_Class.h index 495405c62bfa47..fb9ded3887ad44 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.h +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.h @@ -43,6 +43,8 @@ class HAL_SITL : public AP_HAL::HAL { uint32_t get_uart_output_full_queue_count() const; + HALSITL::SITL_State * get_sitl_state() { return _sitl_state; } + private: HALSITL::SITL_State *_sitl_state; From f59f28b03ae13f6ee4c84a8dd1ee7dcd3160c586 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 2 Feb 2025 14:06:12 +0000 Subject: [PATCH 48/85] Tools: autotest: arduplane: check param values after autotune --- Tools/autotest/arduplane.py | 69 ++++++++++++++++++++++++++++++++++++- 1 file changed, 68 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index c3930ea4c61107..a05ac4f33c907f 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4339,6 +4339,65 @@ def WatchdogHome(self): def AUTOTUNE(self): '''Test AutoTune mode''' + self.run_autotune() + + # Values that are set to constants + # If these are changed then the expected tune paramters should also change + self.check_parameter_value("RLL2SRV_TCONST", 0.5, 0) + self.check_parameter_value("RLL2SRV_RMAX", 75, 0) + self.check_parameter_value("RLL_RATE_IMAX", 0.666, 0.01) # allow some small error to acount for floating point stuff + self.check_parameter_value("RLL_RATE_FLTT", 3.183, 0.01) + self.check_parameter_value("RLL_RATE_FLTE", 0, 0) + self.check_parameter_value("RLL_RATE_FLTD", 10.0, 0) + self.check_parameter_value("RLL_RATE_SMAX", 150.0, 0) + + self.check_parameter_value("PTCH2SRV_TCONST", 0.75, 0) + self.check_parameter_value("PTCH2SRV_RMAX_UP", 75, 0) + self.check_parameter_value("PTCH2SRV_RMAX_DN", 75, 0) + self.check_parameter_value("PTCH_RATE_IMAX", 0.666, 0.01) + self.check_parameter_value("PTCH_RATE_FLTT", 2.122, 0.01) + self.check_parameter_value("PTCH_RATE_FLTE", 0, 0) + self.check_parameter_value("PTCH_RATE_FLTD", 10, 0) + self.check_parameter_value("PTCH_RATE_SMAX", 150, 0) + + # Check tunned values, targets derived from running tests multiple times and taking average + # Expect within 2% + # Note that I is not checked directly, its value is derived from P, FF, and TCONST which are all checked. + self.check_parameter_value("RLL_RATE_P", 1.222702146, 2) + self.check_parameter_value("RLL_RATE_D", 0.070284024, 2) + self.check_parameter_value("RLL_RATE_FF", 0.229291457, 2) + + self.check_parameter_value("PTCH_RATE_FF", 0.503520715, 5) + + # There seem to be multiple solutions for pitch. I'm not sure why this is. + # Each value is quite consistent becasue of the fixed steps that autotune takes + try: + # Expect this about 84% of the time + self.check_parameter_value("PTCH_RATE_P", 1.746079683, 2) + except ValueError: + try: + # 12% + self.check_parameter_value("PTCH_RATE_P", 1.343138218, 2) + except ValueError: + # 4% + self.check_parameter_value("PTCH_RATE_P", 2.26990366, 2) + + try: + # 64% + self.check_parameter_value("PTCH_RATE_D", 0.108, 2) + except ValueError: + try: + # 28% + self.check_parameter_value("PTCH_RATE_D", 0.141, 2) + except ValueError: + try: + # 4% + self.check_parameter_value("PTCH_RATE_D", 0.049, 2) + except ValueError: + # 4% + self.check_parameter_value("PTCH_RATE_D", 0.0836, 2) + + def run_autotune(self): self.takeoff(100) self.change_mode('AUTOTUNE') self.context_collect('STATUSTEXT') @@ -4354,6 +4413,14 @@ def AUTOTUNE(self): self.progress("Got %s" % str(m)) if axis == "Roll": axis = "Pitch" + # Center sticks to allow roll to return to nuetral before starting pitch + self.set_rc(1, 1500) + self.set_rc(2, 1500) + self.delay_sim_time(15) + + # Reset toggle value so the initial input is in a consistent directon + rc_value = 1000 + elif axis == "Pitch": break else: @@ -4399,7 +4466,7 @@ def AutotuneFiltering(self): "RLL_RATE_FLTT": 20, "PTCH_RATE_FLTT": 20, }) - self.AUTOTUNE() + self.run_autotune() def LandingDrift(self): '''Circuit with baro drift''' From 31fe3d31f30d14307841a8f78395583248caa3d5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 2 Feb 2025 14:06:59 +0000 Subject: [PATCH 49/85] Tools: autotest: suite: add `check_parameter_value` to to check parmamter is withing a given percentage of the expected value --- Tools/autotest/vehicle_test_suite.py | 29 ++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index ecaf2b3d41919b..deea94b3e2111d 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -6271,6 +6271,35 @@ def add_param_value(mav, m): return raise ValueError("Failed to set parameters (%s)" % want) + def check_parameter_value(self, name, expected_value, max_error_percent): + value = self.get_parameter_direct(name, verbose=False) + + # Convert to ratio and find limits + error_ratio = max_error_percent / 100 + limits = [expected_value * (1 + error_ratio), expected_value * (1 - error_ratio)] + + # Ensure that min and max are always the corret way round + upper_limit = max(limits) + lower_limit = min(limits) + + # Work out the true error percentage + error_percent = math.nan + if expected_value != 0: + error_percent = abs(1.0 - (value / expected_value)) * 100 + + # Check value is within limits + if (value > upper_limit) or (value < lower_limit): + raise ValueError("%s expected %f ± %f%% (%f to %f) got %s with %f%% error" % ( + name, + expected_value, + max_error_percent, + lower_limit, + upper_limit, + value, + error_percent)) + + self.progress("%s: (%f) check passed %f%% error less than %f%%" % (name, value, error_percent, max_error_percent)) + def get_parameter(self, *args, **kwargs): return self.get_parameter_direct(*args, **kwargs) From 0b7a56e2fd6487a722469d1e21aabf1295b303c6 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 3 Jan 2025 23:29:56 +1100 Subject: [PATCH 50/85] AP_ESC_Telem: fix RPM timeout race The RPM telemetry data structure can get updated by another thread at any time. This can cause (now - last_update_us) to be negative, which looks like the data is nearly UINT32_MAX microseconds stale. To fix this, we copy the last_update_us value before we get the current time so it's guaranteed to be positive. We also minimize the number of places we explicitly check the timestamp and rely on the `data_valid` where possible to minimize the performance impact of this change. --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 39 ++++++++++++------------- libraries/AP_ESC_Telem/AP_ESC_Telem.h | 2 +- 2 files changed, 20 insertions(+), 21 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index f4ff9dea05a224..63e067525bda07 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -105,14 +105,12 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con uint32_t AP_ESC_Telem::get_active_esc_mask() const { uint32_t ret = 0; const uint32_t now = AP_HAL::millis(); - uint32_t now_us = AP_HAL::micros(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) { // have never seen telem from this ESC continue; } - if (_telem_data[i].stale(now) - && !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) { + if (_telem_data[i].stale(now) && !_rpm_data[i].data_valid) { continue; } ret |= (1U << i); @@ -126,14 +124,12 @@ uint8_t AP_ESC_Telem::get_max_rpm_esc() const uint32_t ret = 0; float max_rpm = 0; const uint32_t now = AP_HAL::millis(); - const uint32_t now_us = AP_HAL::micros(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) { // have never seen telem from this ESC continue; } - if (_telem_data[i].stale(now) - && !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) { + if (_telem_data[i].stale(now) && !_rpm_data[i].data_valid) { continue; } if (_rpm_data[i].rpm > max_rpm) { @@ -153,13 +149,12 @@ uint8_t AP_ESC_Telem::get_num_active_escs() const { // return the whether all the motors in servo_channel_mask are running bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm, float max_rpm) const { - const uint32_t now = AP_HAL::micros(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (BIT_IS_SET(servo_channel_mask, i)) { const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[i]; // we choose a relatively strict measure of health so that failsafe actions can rely on the results - if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_CHECK_TIMEOUT_US)) { + if (!rpm_data_within_timeout(rpmdata, ESC_RPM_CHECK_TIMEOUT_US)) { return false; } if (rpmdata.rpm < min_rpm) { @@ -201,7 +196,7 @@ bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const } const uint32_t now = AP_HAL::micros(); - if (rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) { + if (rpmdata.data_valid) { const float slew = MIN(1.0f, (now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f)); rpm = (rpmdata.prev_rpm + (rpmdata.rpm - rpmdata.prev_rpm) * slew); @@ -225,9 +220,7 @@ bool AP_ESC_Telem::get_raw_rpm(uint8_t esc_index, float& rpm) const const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index]; - const uint32_t now = AP_HAL::micros(); - - if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) { + if (!rpmdata.data_valid) { return false; } @@ -413,7 +406,6 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) } const uint32_t now = AP_HAL::millis(); - 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); @@ -435,8 +427,7 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) for (uint8_t j=0; j<4; j++) { const uint8_t esc_id = (i * 4 + j) + esc_offset; if (esc_id < ESC_TELEM_MAX_ESCS && - (!_telem_data[esc_id].stale(now) || - rpm_data_within_timeout(_rpm_data[esc_id], now_us, ESC_RPM_DATA_TIMEOUT_US))) { + (!_telem_data[esc_id].stale(now) || _rpm_data[esc_id].data_valid)) { all_stale = false; break; } @@ -808,23 +799,31 @@ void AP_ESC_Telem::update() } #endif // HAL_LOGGING_ENABLED - const uint32_t now_us = AP_HAL::micros(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + // copy the last_updated_us timestamp to avoid any race issues + const uint32_t last_updated_us = _rpm_data[i].last_update_us; + const uint32_t now_us = AP_HAL::micros(); // Invalidate RPM data if not received for too long - if ((now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) { + if (AP_HAL::timeout_expired(last_updated_us, now_us, ESC_RPM_DATA_TIMEOUT_US)) { _rpm_data[i].data_valid = false; } } } -bool AP_ESC_Telem::rpm_data_within_timeout(const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us) +// NOTE: This function should only be used to check timeouts other than +// ESC_RPM_DATA_TIMEOUT_US. Timeouts equal to ESC_RPM_DATA_TIMEOUT_US should +// use RpmData::data_valid, which is cheaper and achieves the same result. +bool AP_ESC_Telem::rpm_data_within_timeout(const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t timeout_us) { + // copy the last_update_us timestamp to avoid any race issues + const uint32_t last_update_us = instance.last_update_us; + const uint32_t now_us = AP_HAL::micros(); // easy case, has the time window been crossed so it's invalid - if ((now_us - instance.last_update_us) > timeout_us) { + if (AP_HAL::timeout_expired(last_update_us, now_us, timeout_us)) { return false; } // we never got a valid data, to it's invalid - if (instance.last_update_us == 0) { + if (last_update_us == 0) { return false; } // check if things generally expired on us, this is done to handle time wrapping diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index cf4a5a9cc2d573..7b39646b160324 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -134,7 +134,7 @@ class AP_ESC_Telem { private: // helper that validates RPM data - 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 rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, 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 From 4eab74fbc54bbc087082963f845f8efb27cd91ba Mon Sep 17 00:00:00 2001 From: Bob Long Date: Fri, 3 Jan 2025 23:43:58 +1100 Subject: [PATCH 51/85] AP_Vehicle: add comment for ESC Telem update rate --- libraries/AP_Vehicle/AP_Vehicle.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index b4f002d52e6fab..7436fd1da87fc6 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -624,6 +624,8 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #endif SCHED_TASK(send_watchdog_reset_statustext, 0.1, 20, 225), #if HAL_WITH_ESC_TELEM + // This update function is responsible for checking timeouts and invalidating the ESC telemetry data. + // Be mindful of this if you are planning to reduce the frequency from 100Hz. SCHED_TASK_CLASS(AP_ESC_Telem, &vehicle.esc_telem, update, 100, 50, 230), #endif #if AP_SERVO_TELEM_ENABLED From fe0a0dbf920c9d298ffbb4a85ef5780f97da85a9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 15 Jan 2025 15:20:01 +1100 Subject: [PATCH 52/85] AP_Arming: move REQUIRE_POSITION_FROM_ARMING bit to AP_arming while Copter is the only user at the moment, will be useful on Rover shortly --- libraries/AP_Arming/AP_Arming.cpp | 29 +++++++++++++++++++++++++++++ libraries/AP_Arming/AP_Arming.h | 7 +++++++ 2 files changed, 36 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 796136c0d93b1f..d08612bfcfd7db 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -85,6 +85,26 @@ #define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM #endif +// find a default value for ARMING_NEED_POS parameter, and determine +// whether the parameter should be shown: +#ifndef AP_ARMING_NEED_LOC_PARAMETER_ENABLED +// determine whether ARMING_NEED_POS is shown: +#if APM_BUILD_COPTER_OR_HELI +#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 1 +#else +#define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 0 +#endif // build types +#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED + +// if ARMING_NEED_POS is shown, determine what its default should be: +#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED +#if APM_BUILD_COPTER_OR_HELI +#define AP_ARMING_NEED_LOC_DEFAULT 0 +#else +#error "Unable to find value for AP_ARMING_NEED_LOC_DEFAULT" +#endif // APM_BUILD_TYPE +#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED + #ifndef PREARM_DISPLAY_PERIOD # define PREARM_DISPLAY_PERIOD 30 #endif @@ -166,6 +186,15 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { AP_GROUPINFO("CRSDP_IGN", 11, AP_Arming, crashdump_ack.acked, 0), #endif // AP_ARMING_CRASHDUMP_ACK_ENABLED +#if AP_ARMING_NEED_LOC_PARAMETER_ENABLED + // @Param: NEED_LOC + // @DisplayName: Require vehicle location + // @Description: Require that the vehicle have an absolute position before it arms. This can help ensure that the vehicle can Return To Launch. + // @User: Advanced + // @Values{Copter}: 0:Do not require location,1:Require Location + AP_GROUPINFO("NEED_LOC", 12, AP_Arming, require_location, float(AP_ARMING_NEED_LOC_DEFAULT)), +#endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED + AP_GROUPEND }; diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 69e693835b0e48..1ee68e93490d6b 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -155,6 +155,12 @@ class AP_Arming { static bool method_is_GCS(Method method) { return (method == Method::MAVLINK || method == Method::DDS); } + + enum class RequireLocation : uint8_t { + NO = 0, + YES = 1, + }; + protected: // Parameters @@ -165,6 +171,7 @@ class AP_Arming { AP_Int32 _required_mission_items; AP_Int32 _arming_options; AP_Int16 magfield_error_threshold; + AP_Enum require_location; // internal members bool armed; From 569386cfa566b2159199653627c949934091e03b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 15 Jan 2025 15:20:01 +1100 Subject: [PATCH 53/85] ArduCopter: move REQUIRE_POSITION_FROM_ARMING bit to AP_arming while Copter is the only user at the moment, will be useful on Rover shortly --- ArduCopter/AP_Arming_Copter.cpp | 2 +- ArduCopter/Copter.h | 1 - ArduCopter/Parameters.cpp | 2 +- 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/ArduCopter/AP_Arming_Copter.cpp b/ArduCopter/AP_Arming_Copter.cpp index a34eb238bb26ea..b1ed288d9e1f40 100644 --- a/ArduCopter/AP_Arming_Copter.cpp +++ b/ArduCopter/AP_Arming_Copter.cpp @@ -460,7 +460,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0; #endif - if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) { + if (mode_requires_gps || require_location == RequireLocation::YES) { if (!copter.position_ok()) { // vehicle level position estimate checks check_failed(display_failure, "Need Position Estimate"); diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e3a9ac97862d11..eaa65fb82024dc 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -632,7 +632,6 @@ class Copter : public AP_Vehicle { DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1 DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2 RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4 - REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8 }; // type of fast rate attitude controller in operation diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 4ce47bcf60434a..ecfff2862cc27d 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1003,7 +1003,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Param: FLIGHT_OPTIONS // @DisplayName: Flight mode options // @Description: Flight mode specific options - // @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming + // @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss // @User: Advanced AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0), From 5dc77516549e5c1b650f4c8ecafcc92b666fae57 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 15 Jan 2025 15:20:01 +1100 Subject: [PATCH 54/85] Tools: move REQUIRE_POSITION_FROM_ARMING bit to AP_arming while Copter is the only user at the moment, will be useful on Rover shortly --- Tools/autotest/arducopter.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b25ba2fb0666f7..411e3ae7327761 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -12253,8 +12253,8 @@ def assert_home_position_not_set(self): raise NotAchievedException("Home is set when it shouldn't be") - def REQUIRE_POSITION_FOR_ARMING(self): - '''check FlightOption::REQUIRE_POSITION_FOR_ARMING works''' + def REQUIRE_LOCATION_FOR_ARMING(self): + '''check AP_Arming::Option::REQUIRE_LOCATION_FOR_ARMING works''' self.context_push() self.set_parameters({ "SIM_GPS1_NUMSATS": 3, # EKF does not like < 6 @@ -12270,7 +12270,7 @@ def REQUIRE_POSITION_FOR_ARMING(self): self.change_mode('STABILIZE') self.set_parameters({ - "FLIGHT_OPTIONS": 8, + "ARMING_NEED_LOC": 1, }) self.assert_prearm_failure("Need Position Estimate", other_prearm_failures_fatal=False) self.context_pop() @@ -12685,7 +12685,7 @@ def tests2b(self): # this block currently around 9.5mins here self.GuidedWeatherVane, self.Clamp, self.GripperReleaseOnThrustLoss, - self.REQUIRE_POSITION_FOR_ARMING, + self.REQUIRE_LOCATION_FOR_ARMING, self.LoggingFormat, self.MissionRTLYawBehaviour, self.BatteryInternalUseOnly, From 505b373f09bafe289276a5fc8ca8628e7f9df3c1 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Sun, 26 Jan 2025 10:57:20 +0530 Subject: [PATCH 55/85] gitignore: ignore .python-version file used by pyenv --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 48dc8326f8d021..4c3968d0ebd779 100644 --- a/.gitignore +++ b/.gitignore @@ -172,3 +172,4 @@ ENV/ env.bak/ venv.bak/ autotest_result_*_junit.xml +.python-version From a2ca9be645995197aa840e6696c121e24be5760b Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 27 Jan 2025 14:26:49 -0600 Subject: [PATCH 56/85] Plane:adjust CTUN.Pitch to remove PITCH_TRIM --- ArduPlane/Log.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index a258269779a39e..184dfc611a66ec 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -102,13 +102,19 @@ void Plane::Log_Write_Control_Tuning() synthetic_airspeed = logger.quiet_nan(); } + int16_t pitch = ahrs.pitch_sensor - g.pitch_trim * 100; +#if HAL_QUADPLANE_ENABLED + if (quadplane.show_vtol_view()) { + pitch = quadplane.ahrs_view->pitch_sensor; + } +#endif struct log_Control_Tuning pkt = { LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG), time_us : AP_HAL::micros64(), nav_roll_cd : (int16_t)nav_roll_cd, roll : (int16_t)ahrs.roll_sensor, nav_pitch_cd : (int16_t)nav_pitch_cd, - pitch : (int16_t)ahrs.pitch_sensor, + pitch : pitch, throttle_out : SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), rudder_out : SRV_Channels::get_output_scaled(SRV_Channel::k_rudder), throttle_dem : TECS_controller.get_throttle_demand(), @@ -312,8 +318,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: TimeUS: Time since system startup // @Field: NavRoll: desired roll // @Field: Roll: achieved roll -// @Field: NavPitch: desired pitch -// @Field: Pitch: achieved pitch +// @Field: NavPitch: desired pitch assuming pitch trims are already applied +// @Field: Pitch: achieved pitch assuming pitch trims are already applied,ie "0deg" is level flight trimmed pitch attitude as shown on artifical horizon level line. // @Field: ThO: scaled output throttle // @Field: RdO: scaled output rudder // @Field: ThD: demanded speed-height-controller throttle From cdfe93918a48b3b7d7a66ed7143d282d551a6cf0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 14:20:59 +1100 Subject: [PATCH 57/85] Plane: remove dead store of cruise_speed ../../ArduPlane/quadplane.cpp:4260:15: warning: Value stored to 'approach_speed' during its initialization is never read [deadcode.DeadStores] float approach_speed = cruise_speed; ^~~~~~~~~~~~~~ ~~~~~~~~~~~~ 1 warning generated. --- ArduPlane/quadplane.cpp | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 8480a19d03b3d1..eaf767fdfb1c5b 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -4257,19 +4257,15 @@ float QuadPlane::get_land_airspeed(void) if (qstate == QPOS_APPROACH || plane.control_mode == &plane.mode_rtl) { const float cruise_speed = plane.aparm.airspeed_cruise; + // assume cruise speed, but try to do better: float approach_speed = cruise_speed; float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed(); if (is_positive(tecs_land_airspeed)) { approach_speed = tecs_land_airspeed; - } else { - if (qstate == QPOS_APPROACH) { - // default to half way between min airspeed and cruise - // airspeed when on the approach - approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min); - } else { - // otherwise cruise - approach_speed = cruise_speed; - } + } else if (qstate == QPOS_APPROACH) { + // default to half way between min airspeed and cruise + // airspeed when on the approach + approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min); } const float time_to_pos1 = (plane.auto_state.wp_distance - stopping_distance(sq(approach_speed))) / MAX(approach_speed, 5); /* From 8fdfed5249c7815a96718c66ae088db2478a81fc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 31 Jan 2025 14:41:30 +1100 Subject: [PATCH 58/85] AP_Notify: use only AP_NOTIFY_TONEALARM_ENABLED to guard tonealarm backend ... instead of checking the HAL and *then* checking this define --- libraries/AP_Notify/AP_Notify.cpp | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index b103f13168d9b1..8759b2330a4b85 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -421,9 +421,6 @@ void AP_Notify::add_backends(void) // ChibiOS noise makers #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS ADD_BACKEND(NEW_NOTHROW Buzzer()); -#if AP_NOTIFY_TONEALARM_ENABLED - ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); -#endif // ESP32 noise makers #elif CONFIG_HAL_BOARD == HAL_BOARD_ESP32 @@ -445,19 +442,19 @@ void AP_Notify::add_backends(void) CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1 ADD_BACKEND(NEW_NOTHROW Buzzer()); - - #else // other linux - ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); #endif #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL - ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); ADD_BACKEND(NEW_NOTHROW Buzzer()); #ifdef WITH_SITL_RGBLED ADD_BACKEND(NEW_NOTHROW SITL_SFML_LED()); #endif #endif // Noise makers +#if AP_NOTIFY_TONEALARM_ENABLED + ADD_BACKEND(NEW_NOTHROW AP_ToneAlarm()); +#endif + } // initialisation From 8a9a1826e1169bfe2e69b0a78da13bf7422a3a3b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 31 Jan 2025 15:47:34 +1100 Subject: [PATCH 59/85] AP_HAL: move enabling of AP_NOTIFY_TONEALARM_ENABLED out of AP_Notify_config.h this is looking at chibios-specific defines, which is bad --- libraries/AP_HAL/AP_HAL_Boards.h | 4 ++++ libraries/AP_HAL/board/chibios.h | 4 ++++ libraries/AP_HAL/board/linux.h | 3 +++ libraries/AP_HAL/board/sitl.h | 4 ++++ 4 files changed, 15 insertions(+) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 2c97c1ebff46cc..c496eb47197096 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -188,6 +188,10 @@ #define HAL_REQUIRES_BDSHOT_SUPPORT (defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT) #endif +#ifndef AP_NOTIFY_TONEALARM_ENABLED +#define AP_NOTIFY_TONEALARM_ENABLED 0 +#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 diff --git a/libraries/AP_HAL/board/chibios.h b/libraries/AP_HAL/board/chibios.h index e81b3e978bfd87..8bd4e0f1c20129 100644 --- a/libraries/AP_HAL/board/chibios.h +++ b/libraries/AP_HAL/board/chibios.h @@ -155,3 +155,7 @@ #define HAL_INS_RATE_LOOP 0 #endif #endif + +#ifndef AP_NOTIFY_TONEALARM_ENABLED +#define AP_NOTIFY_TONEALARM_ENABLED ((defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM_ENABLED)) +#endif diff --git a/libraries/AP_HAL/board/linux.h b/libraries/AP_HAL/board/linux.h index 705728aa680395..4a3b86d1575026 100644 --- a/libraries/AP_HAL/board/linux.h +++ b/libraries/AP_HAL/board/linux.h @@ -28,6 +28,9 @@ #define HAL_INS_DEFAULT HAL_INS_NONE #define HAL_BARO_DEFAULT HAL_BARO_NONE #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD + #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF + #define AP_NOTIFY_TONEALARM_ENABLED 1 + #endif #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF #define HAL_INS_PROBE_LIST PROBE_IMU_SPI(Invensense, "mpu9250", ROTATION_ROLL_180_YAW_270) #else diff --git a/libraries/AP_HAL/board/sitl.h b/libraries/AP_HAL/board/sitl.h index 4e8c6d961d6f5a..d2296a67165075 100644 --- a/libraries/AP_HAL/board/sitl.h +++ b/libraries/AP_HAL/board/sitl.h @@ -104,3 +104,7 @@ #ifndef HAL_INS_RATE_LOOP #define HAL_INS_RATE_LOOP 1 #endif + +#ifndef AP_NOTIFY_TONEALARM_ENABLED +#define AP_NOTIFY_TONEALARM_ENABLED 1 +#endif From 6f40c80d651d692392488a2b79e5e2fcce2dbcb5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 31 Jan 2025 15:47:34 +1100 Subject: [PATCH 60/85] AP_Notify: move enabling of AP_NOTIFY_TONEALARM_ENABLED out of AP_Notify_config.h this is looking at chibios-specific defines, which is bad --- libraries/AP_Notify/AP_Notify_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Notify/AP_Notify_config.h b/libraries/AP_Notify/AP_Notify_config.h index 0bc83f19051eaf..4ac9425def47d9 100644 --- a/libraries/AP_Notify/AP_Notify_config.h +++ b/libraries/AP_Notify/AP_Notify_config.h @@ -129,5 +129,5 @@ #endif #ifndef AP_NOTIFY_TONEALARM_ENABLED -#define AP_NOTIFY_TONEALARM_ENABLED ((defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM_ENABLED)) +#define AP_NOTIFY_TONEALARM_ENABLED 0 #endif From 613aa6028f707b0bae3407f7f3688aa09f9dc5c9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 31 Jan 2025 20:57:45 +1100 Subject: [PATCH 61/85] waf: move setting of -cl-single-precision-constant into cxx-flags block we have two separate blocks, one for setting c flags, one for setting cxx flags. Move cxx set into correct area --- Tools/ardupilotwaf/boards.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 4fc25ee3413388..19c907ae1f536b 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -288,9 +288,6 @@ def configure_env(self, cfg, env): '-Werror=implicit-fallthrough', '-cl-single-precision-constant', ] - env.CXXFLAGS += [ - '-cl-single-precision-constant', - ] else: env.CFLAGS += [ '-Wno-format-contains-nul', @@ -424,6 +421,7 @@ def configure_env(self, cfg, env): '-Wno-mismatched-tags', '-Wno-gnu-variable-sized-type-not-at-end', '-Werror=implicit-fallthrough', + '-cl-single-precision-constant', ] else: env.CXXFLAGS += [ From eed3e147a0cafdb9f2938bf14dd9245c34974b72 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 1 Feb 2025 19:14:23 +1100 Subject: [PATCH 62/85] AP_BattMonitor: remove use of ownptr --- libraries/AP_BattMonitor/AP_BattMonitor_INA3221.cpp | 3 ++- libraries/AP_BattMonitor/AP_BattMonitor_INA3221.h | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.cpp index b0804de7802751..7514c5ad79a28f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.cpp @@ -207,10 +207,11 @@ void AP_BattMonitor_INA3221::init() } AddressDriver *d = &address_driver[address_driver_count]; - d->dev = std::move(hal.i2c_mgr->get_device(i2c_bus, i2c_address, 100000, true, 20)); + d->dev = hal.i2c_mgr->get_device_ptr(i2c_bus, i2c_address, 100000, true, 20); if (!d->dev) { return; } + d->bus = i2c_bus; d->address = i2c_address; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.h b/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.h index 898753207c18e7..5210e6e5d909e3 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA3221.h @@ -81,7 +81,7 @@ class AP_BattMonitor_INA3221 : public AP_BattMonitor_Backend void timer(void); void register_timer(); - AP_HAL::OwnPtr dev; + AP_HAL::I2CDevice *dev; uint8_t bus; uint8_t address; uint8_t channel_mask; From 9c12476d39afdd718f7ce6d1bc4b7edd49863d45 Mon Sep 17 00:00:00 2001 From: Tdogb Date: Thu, 30 Jan 2025 14:00:37 +1100 Subject: [PATCH 63/85] AP_Airspeed: AUAV airspeed support --- libraries/AP_Airspeed/AP_Airspeed.cpp | 16 ++ libraries/AP_Airspeed/AP_Airspeed.h | 3 + libraries/AP_Airspeed/AP_Airspeed_AUAV.cpp | 234 +++++++++++++++++++ libraries/AP_Airspeed/AP_Airspeed_AUAV.h | 73 ++++++ libraries/AP_Airspeed/AP_Airspeed_Backend.h | 1 + libraries/AP_Airspeed/AP_Airspeed_Params.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed_config.h | 4 + 7 files changed, 332 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_Airspeed/AP_Airspeed_AUAV.cpp create mode 100644 libraries/AP_Airspeed/AP_Airspeed_AUAV.h diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 9994d31f40fc64..9c0783bf83df1f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -52,6 +52,7 @@ #include "AP_Airspeed_DroneCAN.h" #include "AP_Airspeed_NMEA.h" #include "AP_Airspeed_MSP.h" +#include "AP_Airspeed_AUAV.h" #include "AP_Airspeed_External.h" #include "AP_Airspeed_SITL.h" extern const AP_HAL::HAL &hal; @@ -439,6 +440,21 @@ void AP_Airspeed::allocate() case TYPE_EXTERNAL: #if AP_AIRSPEED_EXTERNAL_ENABLED sensor[i] = NEW_NOTHROW AP_Airspeed_External(*this, i); +#endif + break; + case TYPE_AUAV_5IN: +#if AP_AIRSPEED_AUAV_ENABLED + sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 5); +#endif + break; + case TYPE_AUAV_10IN: +#if AP_AIRSPEED_AUAV_ENABLED + sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 10); +#endif + break; + case TYPE_AUAV_30IN: +#if AP_AIRSPEED_AUAV_ENABLED + sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 30); #endif break; } diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index e4f9d760e01f55..19488c7b0b7ea1 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -192,6 +192,9 @@ class AP_Airspeed TYPE_MSP=14, TYPE_I2C_ASP5033=15, TYPE_EXTERNAL=16, + TYPE_AUAV_10IN=17, + TYPE_AUAV_5IN=18, + TYPE_AUAV_30IN=19, TYPE_SITL=100, }; diff --git a/libraries/AP_Airspeed/AP_Airspeed_AUAV.cpp b/libraries/AP_Airspeed/AP_Airspeed_AUAV.cpp new file mode 100644 index 00000000000000..bc40782f78bdfd --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_AUAV.cpp @@ -0,0 +1,234 @@ +/* + 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 . + */ + +/* + backend driver for airspeed from a I2C AUAV sensor + */ +#include "AP_Airspeed_AUAV.h" + +#if AP_AIRSPEED_AUAV_ENABLED + +#define AUAV_AIRSPEED_I2C_ADDR 0x26 + +// the sensor supports a 2nd channel (2nd I2C address) for absolute pressure +// we could use this as a baro driver but don't yet +#define AUAV_AIRSPEED_I2C_ADDR_ABSOLUTE 0x27 + +// max measurement time for 8x averaging differential is 16.2ms +#define MEASUREMENT_TIME_MAX_MS 17 + +#define MEASUREMENT_TIMEOUT_MS 200 + +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL &hal; + + +AP_Airspeed_AUAV::AP_Airspeed_AUAV(AP_Airspeed &_frontend, uint8_t _instance, const float _range_inH2O) : + AP_Airspeed_Backend(_frontend, _instance), + range_inH2O(_range_inH2O) +{ +} + +// probe for a sensor +bool AP_Airspeed_AUAV::probe(uint8_t bus, uint8_t address) +{ + _dev = hal.i2c_mgr->get_device(bus, address); + if (!_dev) { + return false; + } + + WITH_SEMAPHORE(_dev->get_semaphore()); + + _dev->set_retries(10); + _measure(); + hal.scheduler->delay(20); + _collect(); + + return last_sample_time_ms != 0; + +} + +// probe and initialise the sensor +bool AP_Airspeed_AUAV::init() +{ + const auto bus = get_bus(); + if (!probe(bus, AUAV_AIRSPEED_I2C_ADDR)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AUAV AIRSPEED[%u]: no sensor found on bus %u", get_instance(), bus); + return false; + } + + _dev->set_device_type(uint8_t(DevType::AUAV)); + set_bus_id(_dev->get_bus_id()); + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AUAV AIRSPEED[%u]: Found bus %u addr 0x%02x", get_instance(), _dev->bus_num(), _dev->get_bus_address()); + + WITH_SEMAPHORE(_dev->get_semaphore()); + + // drop to 2 retries for runtime + _read_coefficients(); + _dev->set_retries(2); + _dev->register_periodic_callback(20000, + FUNCTOR_BIND_MEMBER(&AP_Airspeed_AUAV::_timer, void)); + return true; +} + +// start a measurement +void AP_Airspeed_AUAV::_measure() +{ + measurement_started_ms = 0; + uint8_t cmd = 0xAE; // start average8, max 16.2ms measurement time + if (_dev->transfer(&cmd, 1, nullptr, 0)) { + measurement_started_ms = AP_HAL::millis(); + } +} + +// read the values from the sensor +void AP_Airspeed_AUAV::_collect() +{ + measurement_started_ms = 0; // It should always get reset by _measure. This is a safety to handle failures of i2c bus + uint8_t inbuf[7]; + if (!_dev->read((uint8_t *)&inbuf, sizeof(inbuf))) { + return; + } + const uint8_t status = inbuf[0]; + const uint8_t healthy_status = 0x50; // power on, not busy, differential normal, not out of range + if (status != healthy_status) { + // not ready or error + return; + } + const int32_t Tref_Counts = 7576807; // temperature counts at 25C + const float TC50Scale = 100.0f * 100.0f * 167772.2f; // scale TC50 to 1.0% FS0 + float Pdiff, TC50; + + // Convert unsigned 24-bit pressure value to signed +/- 23-bit: + const int32_t iPraw = (inbuf[1]<<16) + (inbuf[2]<<8) + inbuf[3] - 0x800000; + + // Convert signed 23-bit valu11e to float, normalized to +/- 1.0: + const float Pnorm = float(iPraw) / float(0x7FFFFF); + const float AP3 = DLIN_A * Pnorm * Pnorm * Pnorm; // A*Pout^3 + const float BP2 = DLIN_B * Pnorm * Pnorm; // B*Pout^2 + const float CP = DLIN_C * Pnorm; // C*POut + const float Corr = AP3 + BP2 + CP + DLIN_D; // Linearity correction term + const float Pcorr = Pnorm + Corr; // Corrected P, range +/-1.0. + + // Compute difference from reference temperature, in sensor counts: + const int32_t iTemp = (inbuf[4]<<16) + (inbuf[5]<<8) + inbuf[6]; // 24-bit temperature + + // get temperature in degrees C + temp_C = (iTemp * 155) / float(1U<<24) - 45; + + const int32_t Tdiff = iTemp - Tref_Counts; // see constant defined above. + const float Pnfso = (Pcorr + 1.0f) * 0.5; + + //TC50: Select High/Low, based on current temp above/below 25C: + if (Tdiff > 0) { + TC50 = D_TC50H; + } else { + TC50 = D_TC50L; + } + + // Find absolute difference between midrange and reading (abs(Pnfso-0.5)): + if (Pnfso > 0.5) { + Pdiff = Pnfso - 0.5; + } else { + Pdiff = 0.5f - Pnfso; + } + + const float Tcorr = (1.0f - (D_Es * 2.5f * Pdiff)) * Tdiff * TC50 / TC50Scale; + const float PCorrt = Pnfso - Tcorr; // corrected P: float, [0 to +1.0) + const uint32_t PComp = (uint32_t) (PCorrt * (float)0xFFFFFF); + pressure_digital = PComp; + + last_sample_time_ms = AP_HAL::millis(); +} + +uint32_t AP_Airspeed_AUAV::_read_register(uint8_t cmd) +{ + uint8_t raw_bytes1[3]; + if (!_dev->transfer(&cmd,1,(uint8_t *)&raw_bytes1, sizeof(raw_bytes1))) { + return 0; + } + uint8_t raw_bytes2[3]; + uint8_t cmd2 = cmd + 1; + if (!_dev->transfer(&cmd2,1,(uint8_t *)&raw_bytes2, sizeof(raw_bytes2))) { + return 0; + } + uint32_t result = ((uint32_t)raw_bytes1[1] << 24) | ((uint32_t)raw_bytes1[2] << 16) | ((uint32_t)raw_bytes2[1] << 8) | (uint32_t)raw_bytes2[2]; + return result; +} + +bool AP_Airspeed_AUAV::_read_coefficients() +{ + // Differential Coefficients + int32_t i32A = 0, i32B =0, i32C =0, i32D=0, i32TC50HLE=0; + int8_t i8TC50H = 0, i8TC50L = 0, i8Es = 0; + i32A = _read_register(0x2B); + DLIN_A = ((float)(i32A))/((float)(0x7FFFFFFF)); + + i32B = _read_register(0x2D); + DLIN_B = (float)(i32B)/(float)(0x7FFFFFFF); + + i32C = _read_register(0x2F); + DLIN_C = (float)(i32C)/(float)(0x7FFFFFFF); + + i32D = _read_register(0x31); + DLIN_D = (float)(i32D)/(float)(0x7FFFFFFF); + + i32TC50HLE = _read_register(0x33); + i8TC50H = (i32TC50HLE >> 24) & 0xFF; // 55 H + i8TC50L = (i32TC50HLE >> 16) & 0xFF; // 55 L + i8Es = (i32TC50HLE ) & 0xFF; // 56 L + D_Es = (float)(i8Es)/(float)(0x7F); + D_TC50H = (float)(i8TC50H)/(float)(0x7F); + D_TC50L = (float)(i8TC50L)/(float)(0x7F); + + return true; //Need to actually check +} + +// 50Hz timer +void AP_Airspeed_AUAV::_timer() +{ + if (measurement_started_ms == 0) { + _measure(); + } + if ((AP_HAL::millis() - measurement_started_ms) > MEASUREMENT_TIME_MAX_MS) { + _collect(); + // start a new measurement + _measure(); + } +} + +// return the current differential_pressure in Pascal +bool AP_Airspeed_AUAV::get_differential_pressure(float &_pressure) +{ + WITH_SEMAPHORE(sem); + _pressure = 248.8f*1.25f*((pressure_digital-8388608)/16777216.0f) * 2 * range_inH2O; + return AP_HAL::millis() - last_sample_time_ms < MEASUREMENT_TIMEOUT_MS; +} + +// return the current temperature in degrees C, if available +bool AP_Airspeed_AUAV::get_temperature(float &_temperature) +{ + WITH_SEMAPHORE(sem); + _temperature = temp_C; + return AP_HAL::millis() - last_sample_time_ms < MEASUREMENT_TIMEOUT_MS; +} + +#endif // AP_AIRSPEED_AUAV_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_AUAV.h b/libraries/AP_Airspeed/AP_Airspeed_AUAV.h new file mode 100644 index 00000000000000..41e75a18c6f804 --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_AUAV.h @@ -0,0 +1,73 @@ +/* + 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_Airspeed_config.h" + +#if AP_AIRSPEED_AUAV_ENABLED + +/* + backend driver for airspeed from I2C + */ + +#include +#include +#include +#include + +#include "AP_Airspeed_Backend.h" + +class AP_Airspeed_AUAV : public AP_Airspeed_Backend +{ +public: + AP_Airspeed_AUAV(AP_Airspeed &frontend, uint8_t _instance, const float _range_inH2O); + ~AP_Airspeed_AUAV(void) {} + + // probe and initialise the sensor + bool init() override; + + // return the current differential_pressure in Pascal + bool get_differential_pressure(float &pressure) override; + + // return the current temperature in degrees C, if available + bool get_temperature(float &temperature) override; + +private: + bool probe(uint8_t bus, uint8_t address); + void _measure(); + void _collect(); + void _timer(); + bool _read_coefficients(); + uint32_t _read_register(uint8_t cmd); + + uint32_t last_sample_time_ms; + uint32_t measurement_started_ms; + AP_HAL::OwnPtr _dev; + + float DLIN_A; + float DLIN_B; + float DLIN_C; + float DLIN_D; + float D_Es; + float D_TC50H; + float D_TC50L; // Diff coeffs + + float pressure_digital; + float pressure_abs_L; + float temp_C; + const float range_inH2O; +}; + +#endif // AP_Airspeed_AUAV_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index bdb4dded5c562c..3eb54c07ad7f28 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -127,6 +127,7 @@ class AP_Airspeed_Backend { ANALOG = 0x08, NMEA = 0x09, ASP5033 = 0x0A, + AUAV = 0x0B, }; private: diff --git a/libraries/AP_Airspeed/AP_Airspeed_Params.cpp b/libraries/AP_Airspeed/AP_Airspeed_Params.cpp index 97403e88b13586..0ddeda5553739e 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Params.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Params.cpp @@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = { // @Param: TYPE // @DisplayName: Airspeed type // @Description: Type of airspeed sensor - // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033,16:ExternalAHRS,100:SITL + // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033,16:ExternalAHRS,17:AUAV-10in,18:AUAV-5in,19:AUAV-30in,100:SITL // @User: Standard AP_GROUPINFO_FLAGS("TYPE", 1, AP_Airspeed_Params, type, 0, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Airspeed/AP_Airspeed_config.h b/libraries/AP_Airspeed/AP_Airspeed_config.h index f12db5cb16c4e9..9e2c46e690837c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_config.h +++ b/libraries/AP_Airspeed/AP_Airspeed_config.h @@ -55,6 +55,10 @@ #define AP_AIRSPEED_SITL_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED #endif +#ifndef AP_AIRSPEED_AUAV_ENABLED +#define AP_AIRSPEED_AUAV_ENABLED AP_AIRSPEED_BACKEND_DEFAULT_ENABLED +#endif + // other AP_Airspeed options: #ifndef AIRSPEED_MAX_SENSORS #define AIRSPEED_MAX_SENSORS 2 From bac78b54bf4cf0b44db425760c9c999c767ce060 Mon Sep 17 00:00:00 2001 From: Tdogb Date: Thu, 30 Jan 2025 14:00:38 +1100 Subject: [PATCH 64/85] Tools: allow selection of AUAV airspeed in custom build server --- Tools/scripts/build_options.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index c3455a5529d87f..d6d85d58f0a893 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -407,6 +407,7 @@ def config_option(self): Feature('Airspeed Drivers', 'NMEA_AIRSPEED', 'AP_AIRSPEED_NMEA_ENABLED', 'Enable NMEA AIRSPEED', 0, 'AIRSPEED'), Feature('Airspeed Drivers', 'SDP3X', 'AP_AIRSPEED_SDP3X_ENABLED', 'Enable SDP3X AIRSPEED', 0, 'AIRSPEED'), Feature('Airspeed Drivers', 'DRONECAN_ASPD', 'AP_AIRSPEED_DRONECAN_ENABLED', 'Enable DroneCAN AIRSPEED', 0, 'AIRSPEED,DroneCAN'), # NOQA: E501 + Feature('Airspeed Drivers', 'AUAV_AIRSPEED', 'AP_AIRSPEED_AUAV_ENABLED', 'ENABLE AUAV AIRSPEED', 0, 'AIRSPEED'), Feature('Actuators', 'ServoTelem', 'AP_SERVO_TELEM_ENABLED', 'Enable servo telemetry library', 0, None), Feature('Actuators', 'Volz', 'AP_VOLZ_ENABLED', 'Enable Volz Protocol', 0, None), From 131c0f8e2d5f77bb16743ec2c124f563e455c580 Mon Sep 17 00:00:00 2001 From: Davide Iafrate Date: Tue, 28 Jan 2025 12:51:19 +0100 Subject: [PATCH 65/85] SITL: Clarification for timestamp in JSON interface --- libraries/SITL/examples/JSON/readme.md | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/SITL/examples/JSON/readme.md b/libraries/SITL/examples/JSON/readme.md index 47b4a85674c53d..306fb0abf55972 100644 --- a/libraries/SITL/examples/JSON/readme.md +++ b/libraries/SITL/examples/JSON/readme.md @@ -58,6 +58,7 @@ This is a example input frame, it should be preceded by and terminated with a ca {"timestamp":2500,"imu":{"gyro":[0,0,0],"accel_body":[0,0,0]},"position":[0,0,0],"attitude":[0,0,0],"velocity":[0,0,0]} ``` The order of fields is not important. +Note that the timestamp is the absolute physics time, not the timestep. It is possible to send optional fields to provide data for additional sensors, in most cases this will require setting the relevant sensor type param to the SITL driver. From 4bad4f856bc3a5eff2ac728b60c3cb7e0173a075 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 30 Jan 2025 12:17:47 +1100 Subject: [PATCH 66/85] AP_HAL: change IsMavCAN to IsForwardedFrame --- libraries/AP_HAL/CANIface.cpp | 18 +++++++++++------- libraries/AP_HAL/CANIface.h | 4 ++-- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/libraries/AP_HAL/CANIface.cpp b/libraries/AP_HAL/CANIface.cpp index 74fa742f9cb77f..bc57034921bba8 100644 --- a/libraries/AP_HAL/CANIface.cpp +++ b/libraries/AP_HAL/CANIface.cpp @@ -54,11 +54,12 @@ bool AP_HAL::CANFrame::priorityHigherThan(const CANFrame& rhs) const } /* - parent class receive handling for MAVCAN + parent class receive handling for forwarding received frames to registered callbacks */ int16_t AP_HAL::CANIface::receive(CANFrame& out_frame, uint64_t& out_ts_monotonic, CanIOFlags& out_flags) { - if ((out_flags & IsMAVCAN) != 0) { + if ((out_flags & IsForwardedFrame) != 0) { + // this frame was forwarded from another interface to this one, so we should not forward it back return 1; } #ifndef HAL_BOOTLOADER_BUILD @@ -66,14 +67,15 @@ int16_t AP_HAL::CANIface::receive(CANFrame& out_frame, uint64_t& out_ts_monotoni #endif for (auto &cb : callbacks.cb) { if (cb != nullptr) { - cb(get_iface_num(), out_frame); + // forward the frame to the registered callbacks and mark it as forwarded + cb(get_iface_num(), out_frame, out_flags | IsForwardedFrame); } } return 1; } /* - parent class send handling for MAVCAN + parent class send handling for Forwarded frames */ int16_t AP_HAL::CANIface::send(const CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags) { @@ -85,13 +87,15 @@ int16_t AP_HAL::CANIface::send(const CANFrame& frame, uint64_t tx_deadline, CanI if (cb == nullptr) { continue; } - if ((flags & IsMAVCAN) == 0) { - cb(get_iface_num(), frame); + if ((flags & IsForwardedFrame) == 0) { + // call the frame callback from send only if the frame originated from this node + cb(get_iface_num(), frame, flags); } else if (!added_to_rx_queue) { + // the frame was forwarded from another interface, so add it to the receive queue CanRxItem rx_item; rx_item.frame = frame; rx_item.timestamp_us = AP_HAL::micros64(); - rx_item.flags = AP_HAL::CANIface::IsMAVCAN; + rx_item.flags = AP_HAL::CANIface::IsForwardedFrame; add_to_rx_queue(rx_item); added_to_rx_queue = true; } diff --git a/libraries/AP_HAL/CANIface.h b/libraries/AP_HAL/CANIface.h index 629432bd1fac11..626c4d3f5950d6 100644 --- a/libraries/AP_HAL/CANIface.h +++ b/libraries/AP_HAL/CANIface.h @@ -125,7 +125,7 @@ class AP_HAL::CANIface typedef uint16_t CanIOFlags; static const CanIOFlags Loopback = 1; static const CanIOFlags AbortOnError = 2; - static const CanIOFlags IsMAVCAN = 4; + static const CanIOFlags IsForwardedFrame = 4; // Single Rx Frame with related info struct CanRxItem { @@ -259,7 +259,7 @@ class AP_HAL::CANIface // return true if init was called and successful virtual bool is_initialized() const = 0; - FUNCTOR_TYPEDEF(FrameCb, void, uint8_t, const AP_HAL::CANFrame &); + FUNCTOR_TYPEDEF(FrameCb, void, uint8_t, const AP_HAL::CANFrame &, CanIOFlags); // register a frame callback function virtual bool register_frame_callback(FrameCb cb, uint8_t &cb_id); From f9a8d9b03405bb1eef414858616981452f6228c0 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 30 Jan 2025 11:58:40 +1100 Subject: [PATCH 67/85] AP_CANManager: use updated frame callback types also change to IsForwardedFrame from IsMAVCAN --- libraries/AP_CANManager/AP_CANManager.cpp | 10 +++++----- libraries/AP_CANManager/AP_CANManager.h | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 9efeb016546831..aeafeec7b7548e 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -458,7 +458,7 @@ bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_com if (can_forward.callback_id == 0 && !hal.can[bus]->register_frame_callback( - FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), can_forward.callback_id)) { + FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), can_forward.callback_id)) { // failed to register the callback return false; } @@ -550,7 +550,7 @@ void AP_CANManager::process_frame_buffer(void) } const int16_t retcode = hal.can[frame.bus]->send(frame.frame, AP_HAL::micros64() + timeout_us, - AP_HAL::CANIface::IsMAVCAN); + AP_HAL::CANIface::IsForwardedFrame); if (retcode == 0) { // no space in the CAN output slots, try again later break; @@ -654,7 +654,7 @@ void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg) handler for CAN frames from the registered callback, sending frames out as CAN_FRAME or CANFD_FRAME messages */ -void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame) +void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags) { WITH_SEMAPHORE(can_forward.sem); if (bus != can_forward.callback_bus) { @@ -713,7 +713,7 @@ void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &fram /* handler for CAN frames for frame logging */ -void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame) +void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags) { #if HAL_CANFD_SUPPORTED if (frame.canfd) { @@ -754,7 +754,7 @@ void AP_CANManager::check_logging_enable(void) } if (enabled && logging_id == 0) { can->register_frame_callback( - FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &), + FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), logging_id); } else if (!enabled && logging_id != 0) { can->unregister_frame_callback(logging_id); diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index 561c9c468054a7..ee45c57715284b 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -187,7 +187,7 @@ class AP_CANManager handler for CAN frames from the registered callback, sending frames out as CAN_FRAME messages */ - void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame); + void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags); struct { mavlink_channel_t chan; @@ -216,7 +216,7 @@ class AP_CANManager /* handler for CAN frames for logging */ - void can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame); + void can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags); void check_logging_enable(void); #endif }; From 51471a0a7ed5419d1f013249d9f38a589b5891e3 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 30 Jan 2025 12:01:21 +1100 Subject: [PATCH 68/85] AP_Networking: make can multicast an endpoint by default also add option to enable multicast with bridging to CAN bus in application and disabled in bootloader --- libraries/AP_Networking/AP_Networking.cpp | 10 ++--- libraries/AP_Networking/AP_Networking.h | 15 ++++++- libraries/AP_Networking/AP_Networking_CAN.cpp | 41 +++++++++++++++---- libraries/AP_Networking/AP_Networking_CAN.h | 2 +- .../AP_Networking/AP_Networking_Config.h | 4 ++ 5 files changed, 57 insertions(+), 15 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 12b0fb1ae3f55b..c5a8cb974f1cdf 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Param: OPTIONS // @DisplayName: Networking options // @Description: Networking options - // @Bitmask: 0:EnablePPP Ethernet gateway, 1:Enable CAN1 multicast gateway, 2:Enable CAN2 multicast gateway + // @Bitmask: 0:EnablePPP Ethernet gateway, 1:Enable CAN1 multicast endpoint, 2:Enable CAN2 multicast endpoint, 3:Enable CAN1 multicast bridged, 4:Enable CAN2 multicast bridged // @RebootRequired: True // @User: Advanced AP_GROUPINFO("OPTIONS", 9, AP_Networking, param.options, 0), @@ -199,14 +199,14 @@ void AP_Networking::init() start_tests(); #endif -#if AP_NETWORKING_CAN_MCAST_ENABLED && !defined(HAL_BOOTLOADER_BUILD) - if (option_is_set(OPTION::CAN1_MCAST_GATEWAY) || option_is_set(OPTION::CAN2_MCAST_GATEWAY)) { +#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED + if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT) || option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) { // get mask of enabled buses uint8_t bus_mask = 0; - if (option_is_set(OPTION::CAN1_MCAST_GATEWAY)) { + if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) { bus_mask |= (1U<<0); } - if (option_is_set(OPTION::CAN2_MCAST_GATEWAY)) { + if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) { bus_mask |= (1U<<1); } mcast_server.start(bus_mask); diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 5c7e8ebca18d62..e9f4c781369f7e 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -157,14 +157,25 @@ class AP_Networking enum class OPTION { PPP_ETHERNET_GATEWAY=(1U<<0), #if AP_NETWORKING_CAN_MCAST_ENABLED - CAN1_MCAST_GATEWAY=(1U<<1), - CAN2_MCAST_GATEWAY=(1U<<2), + CAN1_MCAST_ENDPOINT=(1U<<1), + CAN2_MCAST_ENDPOINT=(1U<<2), +#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED + CAN1_MCAST_BRIDGED=(1U<<3), + CAN2_MCAST_BRIDGED=(1U<<4), +#endif #endif }; bool option_is_set(OPTION option) const { return (param.options.get() & int32_t(option)) != 0; } +#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED + bool is_can_mcast_ep_bridged(uint8_t bus) const { + return (option_is_set(OPTION::CAN1_MCAST_BRIDGED) && bus == 0) || + (option_is_set(OPTION::CAN2_MCAST_BRIDGED) && bus == 1); + } +#endif + private: static AP_Networking *singleton; diff --git a/libraries/AP_Networking/AP_Networking_CAN.cpp b/libraries/AP_Networking/AP_Networking_CAN.cpp index f1b1f7b0f0577f..05237f767625be 100644 --- a/libraries/AP_Networking/AP_Networking_CAN.cpp +++ b/libraries/AP_Networking/AP_Networking_CAN.cpp @@ -117,7 +117,7 @@ void AP_Networking_CAN::mcast_server(void) } if (!cbus->register_frame_callback( - FUNCTOR_BIND_MEMBER(&AP_Networking_CAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), + FUNCTOR_BIND_MEMBER(&AP_Networking_CAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), callback_id)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "CAN_MCAST[%u]: failed to register", unsigned(bus)); goto de_allocate; @@ -180,18 +180,30 @@ void AP_Networking_CAN::mcast_server(void) */ AP_HAL::CANFrame frame; const uint16_t timeout_us = 2000; +#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED + const bool bridged = AP::network().is_can_mcast_ep_bridged(bus); +#endif while (frame_buffers[bus]->peek(frame)) { auto *cbus = get_caniface(bus); if (cbus == nullptr) { break; } - auto retcode = cbus->send(frame, - AP_HAL::micros64() + timeout_us, - AP_HAL::CANIface::IsMAVCAN); - if (retcode == 0) { - break; +#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED + if (bridged) { + auto retcode = cbus->send(frame, AP_HAL::micros64() + timeout_us, + AP_HAL::CANIface::IsForwardedFrame); + if (retcode == 0) { + break; + } + } else +#endif + { + // only call the AP_HAL::CANIface send if we are not in bridged mode + cbus->AP_HAL::CANIface::send(frame, AP_HAL::micros64() + timeout_us, + AP_HAL::CANIface::IsForwardedFrame); } + // we either sent it or there was an error, either way we discard the frame frame_buffers[bus]->pop(); } @@ -203,12 +215,27 @@ void AP_Networking_CAN::mcast_server(void) handler for CAN frames from the registered callback, sending frames out as multicast UDP */ -void AP_Networking_CAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame) +void AP_Networking_CAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags) { if (bus >= HAL_NUM_CAN_IFACES || mcast_sockets[bus] == nullptr) { return; } +#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED + // check if bridged mode is enabled + const bool bridged = AP::network().is_can_mcast_ep_bridged(bus); +#else + // never bridge in bootloader, as we can cause loops if multiple + // bootloaders with mcast are running on the same network and CAN Bus + const bool bridged = false; +#endif + + if ((flags & AP_HAL::CANIface::IsForwardedFrame) && !bridged) { + // we don't forward frames that we received from the multicast + // server if not in bridged mode + return; + } + struct mcast_pkt pkt {}; pkt.magic = MCAST_MAGIC; pkt.flags = 0; diff --git a/libraries/AP_Networking/AP_Networking_CAN.h b/libraries/AP_Networking/AP_Networking_CAN.h index 3e968e4fdb4422..65f4ad393ecd41 100644 --- a/libraries/AP_Networking/AP_Networking_CAN.h +++ b/libraries/AP_Networking/AP_Networking_CAN.h @@ -9,7 +9,7 @@ class AP_Networking_CAN { private: void mcast_server(void); - void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame); + void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags); SocketAPM *mcast_sockets[HAL_NUM_CAN_IFACES]; uint8_t bus_mask; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 342257972f8d7e..74e5f98ece588f 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -107,6 +107,10 @@ #define AP_NETWORKING_CAN_MCAST_ENABLED 0 #endif +#ifndef AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED +#define AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED AP_NETWORKING_CAN_MCAST_ENABLED +#endif + #if AP_NETWORKING_TESTS_ENABLED #ifndef AP_NETWORKING_TEST_IP #define AP_NETWORKING_TEST_IP "192.168.144.2" From 402936abf34c14115e8953a86993c7e91ab8150e Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 30 Jan 2025 12:02:09 +1100 Subject: [PATCH 69/85] bootloaders: update bootloaders using networking --- Tools/bootloaders/CubeNode-ETH_bl.bin | Bin 102016 -> 101288 bytes Tools/bootloaders/CubeNode-ETH_bl.hex | 7275 ++++++++--------- Tools/bootloaders/CubeNode_bl.bin | Bin 34220 -> 34244 bytes Tools/bootloaders/CubeNode_bl.hex | 2884 +++---- Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin | Bin 103572 -> 102836 bytes Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin | Bin 103512 -> 102784 bytes 6 files changed, 5058 insertions(+), 5101 deletions(-) diff --git a/Tools/bootloaders/CubeNode-ETH_bl.bin b/Tools/bootloaders/CubeNode-ETH_bl.bin index b857e8a7b883c3c7d9f1187966db3200f39cfeaf..915762dde376f04427906deae8fb345cd6ccc408 100755 GIT binary patch delta 11256 zcmb7KcUV-{wm)kcXOJ?WAd0{g$^aHn5!4s~;m}kx_7+hzcK}haN28#q0ZWY8CZjR7 zSOT$uBSAC-TTIlL3zkGAceEQctZ8JP0c9`Gi4-+h0)`M%%mz1Ci9?X`P5h1+GN zdfA8FVbi7_;fXy413Lk+8c~6`gOFPpHWD!fQG%#M+(F1~4Es{Vu#FemLb%u#$~WEj z-BhlHTnt^K+J&fK)292KJ5NJK38E5lAK_|e*e3v+dUbJ*!ss-_2K%O-UA-3c0f%|2 z`5N~frX$4D`hejcpjIqP8br&bg)JTVa*`=dl5WA6f*cWtbSpf;I5A2_gJ2kzea18} zfN|sMwHZD54J1xd>(s&Q#Ch_c6DR2;`7CoV$0$Ad29hJ4BHug;*x&*3 z@={VS)xcHKBu#SP*ve?UQqx~8$?ur#!7nFivhSoilPAB#(AjAixG!yCG>09@2QfL@ zFpvFM0+~eaIt1d#FxN{kg>-S7;QO}8wJCiWU&GWMdC3&+$Udi9v6g#2BbZU1BOBcI zfsOQW-vpK9TlZ-AmRQ}BU>`|T1O$9+HyPjS$0%dt-5KT$M%gluQRY>;a-BGT&Xqq( ziWDzlIa%b9=yPK!u(3lKWsfI(`o?l8=fW{ZTzO|3x#p1v7f7OK2viz!J*8q-XNy-_ zm&G0xp2@C!cT(UL1f$44uT5}+M0+1`dfTE!%ge|!@1@X(WOYu1ONPqMLEx2PQF0yl zR+EyGq{>oi9xGx!`LX1MPgbu6thTxlj546og&X?kh~7}BE2ft~=`@`i zzsVM;6O2&m#{Wv*?-Br=$QNDwIu!kf>qh?FWhQ(hYFB0}E6(O< zrn~bjR(~7sq>-tOMcbE^49j5uk}xgOWTe?jyP&r-Ovg$I2mEl08{cAmLn-GoZO&=R zj5pNsl-OpIg4wL#eJoCCZ>XJ8GBRFs+%2MVMGfOt`>rp;jz(i6{TOyK+3oi)ctGU- zOXWAsQtX`y{<>jl ztZXXmr73)MHLpg&cO&jMnz(9cLJ6T34Mk&9``4*P?jQO+|t`-&~8GGwBBQ z1pkqYQk3Sa^FeN7EmKQ*ujy8@LR|$zNq zax;A0`4GbjjS8F_ETNnd8=JL~gMmts)JA>`RQm^5bh=&fk~-QIV`AO-&R@sWD5f*Y z?^k1ITut19V&D}?3ew0ATP0i}_Mh8iUQkZ>m)6QACcvYP33MLbVHhCaYU@+HCti9} zt5YUGUw3|>t=Y&Rzmdp;qYFZ88b6U*snT+%f?ar}Ez?h|RwL!YceU-oc#tFB$%eg0 ztWawmlq*sSF{_SoP%@-EkcxFscB`b(6RBheWkRZxSg9W2pc;|#5yz_Y9MtbfDYYnC z?jRo^sY2?wgSu^vkhr;8)Kp9{av z`p`(bD9bS_rCP(mhmdi~Bv!ca%dHwe*g}iw!Y{UFVw@Jxg`aEPc;x;g7do zt2T6#s#z=tLo}RgpbLMPoYW@5Is&0Ryym0)wQ5#P(-eUo*cDv(Y%(Nt2qcsDLwn%B ztqfJcWb$)p2y*Ngk0z=xKhToFVWH5GWQB!bJ!}f=2-Rd?SQ30po`p^7KY1*$LS;;9 z4yVwK)Mazxv#cg6r5{e&sjU)@(e|l#4(jud)X0>cm^zTG2tVRFc|5SU?Y_9SNZ6TV zPOL6WC1u?MAlGoAdzlyx8s+% zlx{G2MKHvJ2UB5%Ld~c=c$>+tb-p1rfqOO==@{uR?FZvu)PoWiFr}_1;3kK=iU^>u!ZPdUZsrNT<*n1o)qcShDlE9YpH4|wFyo3_~yPH zwM!3~BoX1d%O>XtIlsUn;Y3`hpKGHVV-t?r)0^#ccl(J-?ZT2)Nu#sqkV(csS%l6m zoVRvDAM8S1Ev_nYQtq?zsVOq0EmjC@34iyNlkU1w$@0IoNH|3WsO-WbYxfMM`;>Y$ zH!el2vnwn{XLrk3e3*uml&8L_ks3*8#YQK`#=HgA?VWEcLK2AVLY)f!#<|GLQ$+U^5_Z>f-8Wj z5}Qo}ePWqgN8Q3(>fQJ=2KRm*AdN+#86+rrlp|J5mPL<&-^tbJ1rB-(85Z-Ms5Fmw z_uubEMavP_`!Q^3p5bDD4x~RIeVBL+)c9{`iLJoWuSi@mWS(T+sV7W7(41Y7S3@QE z31sZRh3&%i1Gh)p%rA@(E~-~?u1dk^Tdm~e{ATkb;{Y!9PmjoCtcp#oca09?6M^lD zkRS$qZ;tYyGP_Ww z4)GLmoUDFxj>8w0nBPp7)AVkWfK4GI2e-;6V~ld+s4(?{sKQY>&SU#C7Obl+bKbd@<80<)A z$mPT#j+mBsaT-S~nGE6vI$|>n%Qz>IH#NV03b3V!280>${S@+P@?D3Nf-FmElTRQu zDZSb>Nn;8DBUzmqqPp55=6p`dm3HBb9dLAALi$EEi}VQxeU@BK4S^$urql}nKatv@ zJ%VYDTi(W6M-0VQ8iDu_F&c3!1K9Bx*1v7=9M)43No8js{S;-rrULsWq8^cr_zZCl z<)>jfwG)i-_YC4vqF<8ee_nv~Q}nF>vY$hXtM;mGmnWX)86bsg$7Af6%=xDVWmdY>WIBYJ0I zXUa63pSnZj-2vm&&SVUW5VXLDGYw0ohlxEL_Ge%k@`5lNXsDb?M2>8SlVQ35m_>4R zwX$MNIy{5)&RXM4qt_5GXOJ^ly`dLr%F?@1COZ>YEh2?%&5p)BeSLNxDdlGndCnq- zh0Qa`nw&TNDf1i^t`?`p{y8yUlxz{6oy<$3{HHU?uQ?OtG}`GMV0)6pS?LZdLk(MJ zMTl9B()pAzT~7AH83KFE`AcuMd`+QaZ-L9*|#)FHXpg$a>$=cvmMbJIb`~K`$0kE z%c5~Z5Vx!qCXhkP@8i)apkSDP#4KRnLS!RopE-t(6k$9N;n&joe>A}80-vPuNbly?y6v$+P@8XtiDB;b8N z8RfdnCh_kF%M=T6ye%NJ-+%6qjhIbI!#lfxEloa525k+& zofS@t`6PR5apwr!|BbIs!F{G(7-3(LIQO?D=j><+Ul(bQwa3`8~J zd_KAO*<6Pq@mvzW{V8~oUOTqq2K4fdKF-vB;9RVexx{(rTDrP_vhxGkXym***ATWV zLexjhOHJ|yaaoK`%ztf`aOD+I6+S$;^L1KIT3+**-zedCv_w?M`8{?i9)Bdfo^1F$ zx(Btf1yPE4fjEpUcoDa3+?V7~ zNS;ST`+G`v*GTw!61Bg_pdB^|_qZZl=etUTlTrt zThnZm@Sm6%?Oja&)Y?|C56I5_A=0r{IbTRF?N1LGfc)<(x+Q~(`9q?x3$yH6EPf(t zZ9uIQJkC*i5Q+OD$>HZ{^mE2M^3fL&i55GfeU3s53eDl&88QFTuFQC3%+zHR12GA6 z?NBD-v^o)Q#7!`x{iROK|B5=-Q0F%bbw|wqLYzuxhJI^1-iWJAql@%OeFVzqU}|}V znBRud-=XwQ)YqakAs?59JL=@UdE|Vl(szf$a1$DyiK4W^v)T<$AyC#id?a#jA$JVQ zwYiv#E?)VMi{IH^yEv8%DN{wxX}9;!y46}}-99#od0({m5bXuD=hBgUTs91M1`o>8 z+|S!+2fEbSR?!o z%@UDc@CZmwqPH8L7pAxta;Gl zt-;%yC~=0Ci>YDotWakj(oM=a)hjs>U)mz)uaJ;~A@B`J$Nw+MqJslrJuw_i0v%~R zI1hRn<{Vl8ZnRe(!q(o5_;w!o^RPN#lGzO_0&Vx5+raSWTTe6&c9-3h2QvKkt#W>- zq0f;O;;B@x0d-E{oN#Ik&Rvd^um{)GU-}Enzi02JVFJY&@&-|NdA&_w(RH6{md``J zI77)PYFIwoo~?OmWGlsZg7)A<;o|z5$84-kNJY8Hq@!UgOeKd5;WC%`!1kI??i!R3 zM(l=wPQf`lCSyK`)mH3q3{?h(-8-Lfm1Dt=Y_Cic;iUb0% zxlXoe@ZwL&-OrNoKaeBUk*+mn*xJUE@rTH>YK@FuEv;HgyiWu=mDjKpGQNVuoe&_0 z^gp=*_t_^;Ziicj313HxL|c{`KKkY>kkMPqua_EzpHhRU+k0g0>Dib>em%WLp4KW> zc`0$)GUT7B7DKin{QOn%NT!y>V-{|PZM6PHyy=_QMb1mY(|H72DdA7paN}H~s8m&m zb@ZBY5>|*LLc*^^zM_W4c7B7m#FaF5j-+4ol|Hsh`1NGY#a?11n`o6+$DQ%#$ z%-7_|#Q^w<{QII;$RAeP7noYzd$_`+(LNMwk_?paBkgVc1muhPHKfC(F$H?N%?N4Z zv(c+s#)XNM^7Ct?{MZ`kf8nSobVn`o$7zPqoO%L%@{)QyF%9wOe2b-AF*nJ{=Ne8- zjXv_Bi5=@QbvZbvYPnlETax+|pFaA9ZU`?C$8#CF<4J7aXU07`Cj5E5*$7Iyub5Xk zi(B;=&+d5ay?QCCpvN=Ox{`7Uw~mu?HKq}T)G8Cg@)GBr&(!P65~J&KbRDV>=rSu# zG&1fT>NPs0Bc~zU>7x_5>rX&dp2SA|Ze)73)=%QZUv_9@T@IPpybaHobv`<_&nT0m zTW2maQT*KiuDRYv7n8BA_+%l3*m0VbXb$x-u@M^Gs~d!rX_qYW==#WJP#KmCz)-OYZ-0Q@#Y}wFs_RSV+!ZeqY|Zo$5(O z{g@8#kv%{5kQHLRfB7Ey>Bot2O%{gtFfn|Asaf!{v6#2-88&dyd}P=4pNOOQSu9ijsn9Aeal zU8u*K(Lj_ z$1dc0du$kyUkQLv5_&}gDP-7{aNMWAi*cOnuIRh=G2JlY@*}y9|5C{nm82qU+ysoc`-u+3NZz(`Agn;qxtC(x5`ucswZe@l!EOE1JE zoHrMML(8Yol~YxRVjl@jZW4~!ey9${9ub1^!?p-)Yd)@7IDNtRx#|n{(j##g1+Q_(JQ$hpQIYS$kdXs=&WFmGI zkRN~co^;EaxfsHwb?dRG{(IU6Ecg}cgY59?V%)O7J8dn}7pJw@2PvfOm3y`~X+DhbBA$MCzc=ZzGESpw-YI)5n)Z#Uv@R2ke-SwYjc>7J zE|#F%Q_=10{0!u5v`{xEp+s5a6r|s`&|-{3`pd|PNEeXpzYLrfWDQ>i;V$(IUST&2 zI%~+ucy1)_1_j|uv#KG9dtsy#s#9HCy0^709Bn<0TyZ;BWo3FjsAKT@-UDsC)h^TB zO0C={{cris6`0~>%d~X4?(M2-NhDO0 z(A!geU)OO=r57jRbk*KiWtZ~3(Gi@3Z;#A;oo=d>;-KipxpSe_A!wwR2OS0pt+^)y zQDaMfAX0-`-#AGJu#z*?#Bh-%&B6z*5nPjyVsA3;sE96!F9J3T!xabKD9RZUcdJark)h)i&ku$UaU+a)sRgsJ9reI%nN zw3^G&lU;}lh#0IR7o0FUq^?$VKz~M&rn@1YRO2D0jz*2ii19_F=RGx^Cr9234LM`h z=qBlMs_h!*hGxOZrpr+3hT!7gTxS>dw(`anjV3>)CX(#F7uoBfS;aXinLxWR&=k-> zCw1EYtb(o;HwIe19;b0E(lCop1?3hIXwVeU%z4aQQ8`2>;le8v*jUN=3Uux;E)3xn zE?9XXk*-MZ$7LbBf<-zk(i!O;<~Dn=crQ=$eUL%dHe47S^MubzU^zq~LZ}pHNw~}k z20el@n)mWni14b%m{N$uS9Z;`%&g1`tZ^qOi^1eMnB1kF#?<6&LlESXCk-LEG4{CM z3mQq>eU(=?vnofq*pAbn4Ev-ih06X!7Tpg>d}@#6D0QX4bU03|kmg zv+zxOSZ8L`u!RmmaSNk@EzQCmvkZII{0yt`3AuIOFPydqt)8#32zixatez>0XI8vE z=Su6MuqvjN6`pL;=zLPf>zaiPrtK!D2u;2S*YHj%Ho+>$%o|Kj3_WAg=_G*EJXFEk z8A2 zI(pxF5w}-u`E>h+Hgk4*U`BL`%&1^=%8DkzZYDn()$oio z8htz5GsoexUW~Fyc!P9)Jjk^ah4&)xD;i;vVcO$=0Z0uOo)n2(&$g=9-^VG8WnK#F z$b_c_u#DV%`UUQMRy=zKN6DP$H89H1@)up|BXjwG_4Hl zVfjlovt8HqZ#$T_S&i+%;(7UBKIGo!4U!3}Hy#K#b zgPR{5hCQRut^dO*-~Z(l!#b-=j0*Mp#)CL~TKB_Dvd=5Js=mlR_(;+MzM1O>c4@AU0rp!6G$Ym zS8wovL6E3#^nobI*5ku{9Hdlbbpa<34P9L|w=1lXsJgGg3taq!ssUB=DnG?NX+p)_EF?sK5y}uIThh$(p8?nHlLO(BX<#=2p&L72Vgudd%9jbk} zyqexzC~}vY8SP7a+QzRd7(DW((?yUMKGg3~!Z=9Kw<;kNdg+5y(8p^idO}T(#*lg3 z7~q1qQkAQMBC%V({W3nzGCe=3-)hvY(c1zc0^ZX13W7Khl5>M#4Te=MLGV-r3-v}V z%oLTb(+>}YAKk8@xpT|$yD&x)+pwl8EDY{~sC-S8b9cy)gQzMe3h;tDOpl)mJ%gqy zc?|qZcQFS^IvH(`eFQK zhcTh4zz#xGr~DKDjhB)JY%a=%WB6J=r#(*juX%l{TvK5Tz&rZPG?*Zx^&GoaeIS%G#u2Cxh>MP%<0m!J%|U0!0DPydQCFuEqqEuY(>-{ zAcf(N;4=5FJ~SPhI#xd_9kxryV;%L^H>JY_IHOM=0X;%876c{u1b{_nZtqRruEXO7eH^+tZ*YFjecOLB9C! z`~fo|qH5Mm*d_ZrH+2>y>o?DW@qcHA<-$T>^!0NLxL&+Ke|{Mj@w$G{a+vp*TR!?1%b{~S-K&6F(9bD=&~{F30Sx}65HjM< z;Z?(N#Mg*Zh*HFdh%JcE5aozti1mogh=Yh-h`orm@?y!l>hBc7BK=z{Ah_K=G7GAd zD{&HYrki@YF&&kw{N=O_>Rzsv}RNnWiFD~175t2>S}eO58f%9Z+( zV$gWs3_xvv{FoNQEW{Ahc)VJFrWjI1eb?ySN?@hj!xMAtgi~A9))ElJ`cvybqW^FM z`1F5;t#M@(uyzbt{8Y&m;e)`>N*MZ4+hcri!ziOfUXg@h!Z93yVSoMo4GmWvVYE^PVdE}H+#|9t=R7@p_loS8E-XU^QYr`@g8 zN>=QWZ0Zh+H}?om3q>a(iV(XH-yoV1e+sZX*HOaxSM=b` zyAxpa=6in50oD!{FZRpkd*0ru$S6YWLYzaiAesO+NBBAh*eE&`G2gbiXBW>&y}@pr z*L;n0XmWFPq%gHN=#-&xM}#5%^G;9>l$=r_D2k?^ zQgleb{Gb(1#Oh-b9?h4 zY@V!}OK%my7$S8Z0x@Km^92||d|k%*y=`=E$tYp#sfHteQY&`n{aaDGmU%X<8znzP zHn{AE7o@lAW~d_Hxb_7-vA8C~c9J9u46Lvj4NLn_^0)+7iW*4C+Xhhb!dhphGt-rE zW)F~+vOl4iEOblqp_c(2HUm1Bx4>txjEqid#CKxMYZ zg zCW}z+%I>jbu(n87_L}7@2QlMzEs}9zH;_wR@&g*N|N96QVMbJsr{pomC|c@E(T-%a z-yrys5Wl{VM=tmchOwlR{~*XFss4Q-f|UA`<%7*}FGedx%`^xrDYnuk&y&}Dov)he z%9^c4LkI7qfof2X0{W7iqAAQT5!EJ+M4GO(aatQidDMy+V27Js*k_i3aw(f*bxfCM z4OB`~<64a}>H`_;WOhg&sB}op%6iQang!Leddj6?u^&YbL}McYC_0hs3782Nh_vgw z(n}^WW~Yojr`ym~2yU4ul80D~xQm!b_5}9u*kY3F`=zQer8k%=YuqB;*&oThzzYE{ zQ6hRY&;t>}5m|_(h;jrW=j7WVjN~X*hN_M76_FZM`N{;R8&t5o9Aaf`7o)0NoCpJI zTUJDh^x{Mu99%2@1W7gDN3B)MI%o4E8o#&WrEg5&~|g>dKoVWzX!XuI#tdf3W5iu(;e;Uc$;Qa92mf997(5;aQava`i7$Cpd+Pi#jg7~Id zBTs~AS2n`hYM_w+kVw1rUG8U91qhUKg_=3t&57-7%?S`Hl}I_UF4nzR54P87D`t;S zrc~Q0KuRX0m9ciJ%_3@cLn_Wr{fU%2QYm)o2~wSfa%HBSdWe*dFiu%$r*0!9SEFdP zo%|6=1yaZDRHG$|q5BMAXr-EgzE13S#L!IvbwnBx13Ss!knjm*mP>}czV`M$PV92a zuLeFvX@*kBl_~}{LDp%bQ0BxITT}tCjUS>DJIj)Tb$)?h=;Iti8&2<_piLHVnCTFJM`g4{3_oY=`^Nazq4NY;e*z!$eR zQ~{af$IuYu*svZ>6k!42PX>pDf&2ST>)T=yy=e5{)rX%dV+Vw>KTQi-EohUYQPsZhDW z=ov{78QWr8Q6p1Q3ODwJ(WZ91AvS_*9usAM(+##m3D28AjtiJvQe9X-6kk@lwi5#k zq)6F|?PJNA-ku@1jjwxeiJ@o>dRJI0VLqt#WE3Zb8V_BX5-P16MHsS>%B z>(&;&_?AQ7HMyK-AGL`XSq&&`++s`jEUNpICM7dARftj^ZDTT~VL8{P)=+9wBc)1H zN~>%F?jhM4t$cnO)VQn=+-iil?@cr_sJWShGwmVU9OR+1~9U zm8_+0YAhy5d^05!SJ7-!8>RlNF^Y*pd2jQ55)m`P<6VPKdMM+aCL-d4?kU2pQnm{r zF)_(w3<8EuJ#UzYfhkAu3#b1$ppRfZKANH%dEN>^+zTxE`8ycrZ(}V6T?M`4s9Q%} z!rPi$*e`UhecV8-M#VWKxbH}N?E_NMcQo84KlGh%r}vRzvEK@!i-}ji11`Mimxyb9 zC_1`WcfKD3;u}ccCY}RST}#{IYA_v2lS+ro70o^UnCb(nuS*N-c?tP=^3H$-uY{Wh z?CSf%^xOd9f+hvyEawbflfn2Bl5}qfx}=Q z`E%ewxJ&*uNa4#%9K)6roRBN}Q}lbdFIvHa+#Hk)yNKegk#4+9Bg#+{fc8f`BCFpj zu=^5AOmAgK`Szj6Ura^}ZkMjd8qe8FM#pLGQm09C+(-ePO_=ytI3iwPUW$}z7 zU+q2-=-7$m`rpZJ2{R-etz=8WGD&nXK8bANH6#`mkc=UR?QNM8i6C*jlowlpM)r~E ziBrTpb()+@^uw3@VPYtJNL-VG?c7JCUs7MYqG%FXkkqZi{v`5AQa5}1C~_%jh`qLy zcrq$`Z6_JT46xUZ>q;00ffsN7?j+nsAfhJ&Jq+PLnS7LT+b%VYl%#gZZzJ`o5gnSO zIhDXIvN|n9@ok%s@i{4#+qkc6fUipf(l_)p(kJY69l4Yi0(*5WY3BgWlZK%^y74_e z!CsuEV3hGGWg<2qMj_~IpvPhvJVoa|tfwf7mz{=m9LnY*wjhGDfIfvKi||4DY;5Q4 zEJ1#wu4qIZxEZl(3<4?>OWu4H={NF@M2^BUvq{%c%fx(jJ=rrV!(OW-Eu(M@$TK1u ziGK7Sjy&Zv73ip`y3gNf6ZrCU8q(ttxrjnEyBNzOx-;W+0x!P#F_Np0U5?k$W#H*}ir?3CRC zujN?h`)I_H8J%Gm(X-QvP z&f`nk0Tct~pEJkMk!-97VZCfNS-boToS$_GD?|X_k>t|p zxL-J2>Mh~bKAug^mwqmYEhbCey8 zhtIEnWL$Y1%{QWX|2d@Fs()2Li+1DI!T!iz(*u-O@M^w zIu($FHQglgg_tS}$(%LM?6Q#sJgJ*e-W6abSzQqhNu;JC#GTj3!ZyCk%C{-`oC4kN z74G2my3baew4Y!RwKE)KFS%{RAEP8 zq6Xc*!S9Ea#s757hm0ns78E&O?R;Ts+jEF_Mvp+NveTwzD)*g50UUS z(Oi0_jcs%H=-0fmpJ}wEx)>d_^h(iT}GWwkaj9$rN3IwVf%Z+O)_r(1Q3(j{mFI(pZP>^ zpr?3iy@>sW#2n}`Xp2?EJgN!T_$?B$tWXv%!j5)Zrl^Ejj}5YBS63l!%09Gssag#p zcCC?8-^TX$Egb`UkNoREh&at6W#^F#2Qor>BLBM@{}fPAe~4r@ZkA1r!|#V$8&GQy z9>#b&io}1KZ1*#0KCZO$$(BzelUN(2euhFXam!l3x>7>cV3TJ(G~{Tq%7GZUVjENm z7_~;g-a-jV{Zpfmy^cCpQRgQ!?~ahYOdKkwhw81zn{oKfPU6Q+ktja}TdQk?>_(LS z7NrU5t5JFl*;*NHkIB&auVR&$dD>URL(1Ve~+!dnUC!wgOGJad%vPRk5|1okgZk2aA)wKD&6&jl~16C z_Ktz+$e_<=!zyy{vzX8g_`KwL0q)ub?6>#^2r7l_LMuP~QFfhi?Gk%1h7sw(V2}P* zO1%&J;7>XoVa4bl%<;O0w2(Dh_+H>uFD({w;$WC`3U2eaVGceZPY-&ler)qn;oVD& zFiXwE)>F9oZ!`_@7c&k`az?=JY?HEQNywoPI7%|`|8BDI&;VFLbcd2*B56M~7nHh! z!}Gy~&&m>f+S3qQ=aUzoD+4o3E*J>39bJ5vV$ZgpXddh;xhV~z*zek||S>>WP7_72^5VjS++ko9Z9YaaJx3_bxUYz}MY@`=2pSb`XN8Pzt zDs&Y6!2-h6z5{M#S8cigC+**BXL#(xwr2>ThEm|2NixmeB{^Tjc$L_E^r4I}1=#Uz z7-@c9DUDo6KL4Ukl8GzGL9EubzOH_D{FJ9NUeN)246o?KX=3{o9nA_!i9Xml)2hO2 zJ2`VNSHhkqNAyw7H73~J!IQ9i$Wy&a!e0y>D?;s_SEAc;>I;zYcaBd=bi+?8K`?X~DLyj?o5=k$WzxazLWQRsr!8I4 zS9&2#)`g$_K{(>&DH@MixEZ$c@fWa9PQ4y-VKSbrBk5WZ`?(c2&h@fdMU7CyUouX> zfQTYR>;mM=>iHTug?GHQeC;^NIPWL^*(PFFkb?6OZpUqzHT(QtVp@vt^0Q1eIdVP_ zJ|o|s_YApX;d6m%*oHof()k>UGl~X?*d$vAe;)FM>=M%H!szAeY*quLkIh4`8Ym|! zPRwfR#cWzV^gDM{5W2g8`r`~msZKwJ-i67=TEB8J}t)0cJdW7e1hEfjKTst~P|Gs9j zo+5u-2wh%LEkdherrwxRh*s$gmXabI9axbAmYph-`ZeZjI_VE;(rd=(RT{ayuY>l! zG<;t%PYwEJ%C)VjHzWK^(oDM?Hqx6eJ*E!&Xz1P}jUxXKn7K)Z9to+bOiPoGCW8g( zMI%M+C_iKrMdG=AKG}HD)A0v%RBB(*$mxq=uH)O)0pB#!0=z{^Y~fZD)5V+8GMu|2 znO5#Sa_iC>>07U;{v`i$29%SNmwQO6F}CJqc93^u|nat1Y@Hh?V3W6(#m;N zA7zSOn)aJQiY;^-`SN@J<$Plyq6D$hffo@sI^Z?^7ex*z^t;K*eTL?%(LA4HHm(UT zDYv2QF9=~|Y^|IXQa0`oF1}W7D~>3!X0L;|QH&PW7m3iqIg=V&HlcoOJ+DWt!2U3Y zdAO*>WK5%*AZrE5YxD;nvZgT#z9IU?sO5zwRW9BQidA~|w0#N>G&IwcldGz6O*^1) zLn_PkKqG2)lBo2KX;lhm{?9g5zGoj*W` zN`dx8^hZ#&71gmdp(<)qF3unujM7LOS3%pP_FF44DQZdN=!#+M!wwHdm691h zD4ieR2ayjs4m@&+XG#ukx+>xxdhtX6K4X?mWOn@VP0KL+^rw?4>A*MDGCM^11MU-ied*`FPN9`+;!KMn#{a`?x9>7N)W zIo!nDMq6L@hRd0 zf{)g1EdR=rUnu*`rPg=B5zcn=#Swl(;(wmv_d3S0wVoJBjou3*bfL%#+i^1ec|^|Z zc4MuW@nZZLS0+>+f;J-D_;(<)efG&9)Yw)Ogj8z#z?1x2Drb!Ku}oA&EB8@*BtF^E zwid(gn!XiLjD>5*E$Rxrg=?|oy0lY0zQ-lzWJ1T(xwFU-ExNXM z&lNYzD60FVCaUMxO;k{WeY_$(?sY>%mjRuGr?E8>HDVFbWrVq-gg}yeC)D+_Nu`;f$=BOdj(1x*53=WuH~13$ zou~-bq+lH6RFI7uU<|y=PwRZDS-5%axSp%oCY;D|P~*%#H9U7C@x80Ezd#qUD_QLj zjfe@ak)iu3MKW~d1TGEXHBK0+kSJ%QkK)1*UPB`t7R3ktGgF7Xp=L_O_xm7=U%9N@ zGyBx>5^XA1<0TY=s}<&on4B64J%TE}@3rj^>Dh!eIX4JDXRESva&u}h<_=I5i_Pz1 zvu_h$>q&0i4Tcf|_d;MW3B4Bq7BcRh!c%Qh7Va1s@*oty#Ls@9z|+>o2g%`WHVe1xFJmh)g$wwcSR@QT)zk@}-;r!b zOg~xNOI+{ZS3gDYkCffv=h%U)R)7wB*e5`FxVR}(W8(73pkD{L<>Ep9MvYt}#1}w@ zPL3fJzbe8<8C4pe)UldYZo6@p(IHY*B*109vw}{vaPFoJMhA*NFY=R3IJx$#A}G(M z(u~)rmOyxH1E@R}UN^L;J~yzcLxzBR9bVuqdY6Z4=Suq!Nd?`@#A!&z!@jVTta%s+ zLFChigWXXy%UMuqG^`!Y?!m@dY@KTds}(t55Nn@aoBx8G@w4&3vbA+)<)4DBK5Ps_=Wg ztQtxquW8{rwUOTpN-z=WBfn06nBwuHTdcf=OCb@D205=n;S~tF*22xyEq*i;z)g4W z@k)X7_wCB{_i&b@sXsX_DSEOTZylSTe2PEl*#7h>oFZ$U)#D9V((_wlDAFlfc8He8 zv{CfChz+K{z|Eu>(-8=Z@ho*)Zo?!pTpjf=+^(^l;8hx3V(~CtT4!wYYgRO#LIjDib%aV z7$%bkW`$r=nNDK)T_C6|BQI>{v8X)-VIo20n!4Xba223X+aQ4+Fi!ha0#o3gc9;X~ z5L9EU1N0Zf)SLI_h9~aLRx^7w6a4mO8S9;H9`W;GdNIwo{pio!(?ljVLwiXEfv`^dR0iSB^GzS;`q)42Hgg5qU^nbwk~Y;1W<$5SI{cU@ zbj06R&^`$N^18E~K_r4|?FAng1Uhij^U7$>)peyhb z1^&G0OH?ha{Rn^GL*s9Npo(I@GD0QGWox4X!6uoA%`3{aedLhfJrL^*VuW3V|Mc(7 zu-sAYMmczTuQ5^TKk+*={?viuH*Nf~$Z|WiC*?2(GPNEG2!#RKK?>;Ysm88(8cQKGmnE9w%$;5G=>SJWxHLzWa=>Q=@8-Z%Hr_U;Q$ z;g>o^EX))*HlosZh^PJPw)BTyATU?dogDzzC6d_nKxeG4`y>ILfgoy~c1t3(^5xnj zV5AqZ@g`zu-OVJ(1$bXOBpC=KYJW_|C)7*Zjz72Rnz;c(i-<(f2zLa9f4&URE*t8O zra)I1?UsgL+z@+G|BnC0i%Q4O7%1z3*-*IhA9UULVXzkdgQ0yk9F(wF>y`oDzQJz;or)+$>_YdOWQOKytNa@L3eH0IAH#XT43F?aqtDa zxk?sv(SAJvJnODcfL75z(Mzhs52S^{f1={2t(*qk>#j_LPbB|D&qupCACiI6{+JKr z-dvH7;?P+*3sld6K<%7DaM1of3mo6rfT9rmwVt!VyDn@tOn&pAqF#XZvpM)iQQBK` zAorhi7@(a|0CC#N0+{zt)Fy;d)SG5kX(5F7peP&u{R0)b_F5q(vat{*zIi0v=7E>C zpcr2gs!m%B^Z$|NAZ_M6nD)j|(9eU>TG@Pvd}EEI`4C@MJ|E0tcmB54ET*V-ME#k} zYsVLAKYSM!z&Wk+QkeV37V*jZXm>3I?|<+(>@R!cQV7$UmxB6@yRxgrm4I41qXeer zOvFo_OvEU}SVSB`jfg}|5f2efhmX1R ZgsYYIUOD)5-qi8yYwCa3td5q<{{hx=%ai~B diff --git a/Tools/bootloaders/CubeNode-ETH_bl.hex b/Tools/bootloaders/CubeNode-ETH_bl.hex index 8fabf09f9da32a..7cb906f86651b2 100644 --- a/Tools/bootloaders/CubeNode-ETH_bl.hex +++ b/Tools/bootloaders/CubeNode-ETH_bl.hex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diff --git a/Tools/bootloaders/CubeNode_bl.bin b/Tools/bootloaders/CubeNode_bl.bin index bac972709f9b18592b8f5cffc6e004b2171d1f6b..5632578b89c11a0057b4ca12cc75b68e79ffd547 100755 GIT binary patch delta 2498 zcmX|@3s@A_702(Hon>d`Eg%aE?CdTZK!QqEM5HDtaCr+pVz7KDmKX=05VUH(SP)E# zB}U2Bh*DCCC5erO$CNK(-6B@JfS|EXvyehggPpD15*+ zdyfSEx{?U_nM8~kQgV;9s;LJhEu3OvJAKMvH5>4WfF4=vt5$iMCIhm9_WHKXPUn;q zruVnNEw;?R4it6+@55|UfJO7_q)0iXj@1R^LJJ!Rh=XYsI429fX2o;%!wYO+P6@os zvI46svZut#1(La@db!6}#3I(fVqSTE%3PyPfy9o{%K7HXhc`-Xys~i0Dq+m(j9H8R zbz{&zFPDgeD~QM|j!R^O6p_(Nkw~R!PX8U^RJ^k95+UlWU`d^&uW1ObUe4X}N#PZ* zOGGS9b3QvS1Uuof^pXz4+DoL%8GNe!Sc&daNMgpID0o@U3etd9s_BSVe>>W(!UL4>lHT*8Y8(r_M2XF|&Sa z^quLBQDX4zCE>GHxaR=IV<)XOXO^pPMM`1{Eaa7)6OZi9*;!bpKE9%3+#Jf8L}Mhq z{0ygjGF}|2GMP|u%17g8(6_k!_s97WLFHqLbg2eZJ}SYq*rkr4@s1UvJ9mW)diQ@G9F8XMTt}}MN)|8l%KE@Ax2oq zIz!@M5&J$Qxjqc!9OADn7$DiY=abxa4ln=yC7hg>@{{7zhb+oN+tH^9o#GADAD3 zoi&CZz_nwrG{Q@=%@WVympB^nDX5*xwMK4>G6M{<{<%AGIi*JbT-!gRG6smC^vV6v zohtZDJ~ID?%J;VygbomA#x73V28AS0&araqixq#y-ASbcU*MFfE=c&ior`*}i+tBj zi23pmSWDAlh8)RZR9~Z}HMBsZyNMGT(P^_&{d$X~t!>d#B>iSaX7 zX_0gxO;|W=KO>Rodwt_}5N(5w>hg|l^x&Wy0ZL3Or2h6Doo`F)I|)l%7*!E7%+(%h zS5UfBV1cjgVt6@{^+0^*nt&)4^$5L_I#S!A|-e;CXSJhA zX+qq8>}39AUjbG9#(hNaIPVZj4-b=Cog`RSJNS@5TAZr7zJxyN(@Beq8ft!52@x}6 zug>u1^Dz!#fm!MqBB0+^f-Ac|?JFF#w$=7uuGTiF93fpT4@f1xAlD`HaYq66$j28| zbDnVy(^~^2>JfoVk7=1Dp#pc~=7bNSf#ob2hH#dcXoG9=c;Yu|_)_j)rg!6n1MGg< zpPc6R>GzZ5UsA+l$9gr5JOpX0=`X5qa%6E1holB?2jx*0} zGgPzK?9iZH({OSLy(`6H)(%(JklmRh$(yqeb0Es2D;Q|gar4Q@Bf@sMF3*pHoveA4 z0XDE}tD-$KCQp~>+I&pJI5n2c9T}p(FI&1kIr%O0-bI>_QrAx4Nhim4JpQa*q_9x6*S%9mOKs25D2(PlCXo;N zK*WuZ;MbVzJe4NL^4XR3FM*EfHyA;~mTs`l*^9NE{Z*nRgChnHWLBm8=7xhR?;lNm zVdp5Bcf7COPP&edp-sTm&^9$Y9Lnb zuFQhMjukjG#U^8svcg6rCC#z0h(ENm3hv1ArZ7lGja$?#%%v;Hc^!cMJ%dztq&?e?ei=1YN*(zBVFjl*yLD;(_fo z(fNWdpL~k6j!v z4;Js#J*?~KYgg^NeycobO<~d_tTF!)zQx$^7C3?@!)L)6>qG`OOfq6C9EX4Fy?|Es9>$@!c< z8?94P;W{pu(gKh0COvy`qb1e&>Zqh}`W|et6hj;KTC(ALjEyORFR?OaC%CaUrV2{2 zD7LXKXH2TkROP0|g<=0>sZtZn=Jn}ga+9za=5-9#zbMxa+^qKSx^v8}lFuFVxhuZ8 z+2@^B%%r|$Oyc$bUSd90!3OIkrdH<#?ccGW;`J?;7!!&TRH4Y)bU2}LA$KQoF|Tu% zm{gq?%$=4TYUVDBN+X(qfpw>y;xvdV{-*$4=|4x|73l66cWYPUZ3o zoc@R5$|QrsL5kCVKio!kYRLXznD>c>NQX0|nn^_(M91uqY9bXyDkr3Nk(x{@Kcu#k znqrU~%R{P`RGcBlQ5{mRlaibidM+e4lC+b$5K`-gvlMaWJVkUk6_~~8tMFi=9dfZV zF&n1h{}NqgQ--g5+u}q0GdbNn{Ky;K!7HM|?2!C|yBbSg{+{k_1gPAySzh_pV2vSLmF zeK&rVlnWcsl$>EHr1)E%q9fQBnG&VYy7e3^N?ruX*qodJi_nv7hw1q5_!0Ix8oyJupmyKu7- zsjg68Qw*Ppa#q1Ks^WvVK{{)mO(l0PV5PHz7Z+fXJr**wZ2K0DH|T?1__6#WRnw7_ zT~s@^)FZG$^Q6w=V2L)E_6Z2Va;?_d(`A4gczfy_ump2mZ=1RU2D?Q9{hD^$)oFl> zTJwuH4N)g9h#epWhAxhK`otX2k72EQ<=QSfoeX;T1y0wyU{3dWF8yd1`|b*3^5uST zSLgXVtWAOvu9O)qw`eoIIOC;-kvA&Ul6IHsRPJtW&1+MyoS&{#sI7V84BgwNGMBGs z*b9>1gPAjO>h_-FDP2%J{`_i67mIafA|@Jj-bn4F6S;G4Y*r_Ao>Gh2S9i*)6dLqY zXizmcX!c`or;kO9^tctnpC71ueZ`KmC_X9L)XJ$5X<^_Jo zyS-I{Ph{gm7Mwq)4o1;4=Qte4jdLGECYH?eK#vyn^Sc5()E+OePT=%^tkpVJc>wNVZRvdO>1sS* zI-L&ZZ%P+H1E#IX0##eH<{t)oP9qbS(3LhoDb*bx(p4ZTQxrJK^uPGw#OP2ut|$)( z?^EvuT)A#h>{hbgB=&~lgQaa&Mu)cJ*>#rKvZu`XLk~!FlCg|_e{t|y86A2B@2*=7 zDd=8rhiF{6-W^jxa|ZKOYFVGp7DjwuryX6t+YpgI`h}NM*t7#ZtzOo(1G6e!;KK6C zU%(DLLiP@=yYfBS)h1zDc} diff --git a/Tools/bootloaders/CubeNode_bl.hex b/Tools/bootloaders/CubeNode_bl.hex index 954f6b13fe092a..0641d600dfc474 100644 --- a/Tools/bootloaders/CubeNode_bl.hex +++ b/Tools/bootloaders/CubeNode_bl.hex @@ -1,34 +1,34 @@ :020000040800F2 :1000000000070020F1020008BD3300087533000826 :100010009D3300087533000895330008F30200088B -:10002000F3020008F3020008F30200084544000848 +:10002000F3020008F3020008F30200085D44000830 :10003000F3020008F3020008F3020008F3020008CC :10004000F3020008F3020008F3020008F3020008BC -:10005000F3020008F3020008D97C0008057D0008BF -:10006000317D00085D7D0008897D00080945000894 -:10007000314500085D45000889450008B545000880 -:10008000DD45000809460008F30200085533000862 -:10009000F302000865330008F3020008B57D00088C +:10005000F3020008F3020008F17C00081D7D00088F +:10006000497D0008757D0008A17D00082145000834 +:100070004945000875450008A1450008CD45000820 +:10008000F545000821460008F30200085533000832 +:10009000F302000865330008F3020008CD7D000874 :1000A000F3020008F3020008F3020008F30200085C :1000B000F3020008F3020008F3020008F30200084C :1000C000F3020008F3020008F3020008F30200083C :1000D000F3020008F3020008F3020008F30200082C -:1000E000197E0008F3020008F3020008F30200087A -:1000F000F3020008F3020008F30200083546000886 -:10010000F3020008F3020008A17E0008F3020008D1 +:1000E000317E0008F3020008F3020008F302000862 +:1000F000F3020008F3020008F30200084D4600086E +:10010000F3020008F3020008B97E0008F3020008B9 :10011000F3020008F3020008F3020008F3020008EB -:100120006146000889460008B5460008E146000817 -:100130000D470008F3020008F3020008F30200086C +:1001200079460008A1460008CD460008F9460008B7 +:1001300025470008F3020008F3020008F302000854 :10014000F3020008F3020008F3020008F3020008BB -:1001500035470008614700088D470008F302000892 +:100150004D47000879470008A5470008F30200084A :10016000F3020008F3020008F3020008F30200089B -:10017000F302000805710008F3020008F30200080A -:10018000F3020008F30200088D7E0008F302000865 +:10017000F30200081D710008F3020008F3020008F2 +:10018000F3020008F3020008A57E0008F30200084D :10019000F3020008F3020008F3020008F30200086B :1001A000F3020008F3020008F3020008F30200085B :1001B000F3020008F3020008F3020008F30200084B :1001C000F3020008F3020008F3020008F30200083B -:1001D000F3020008F1700008F3020008F3020008BF +:1001D000F302000809710008F3020008F3020008A6 :1001E000F3020008F3020008F3020008F30200081B :1001F000F3020008F3020008F3020008F30200080B :10020000F3020008F3020008F3020008F3020008FA @@ -52,37 +52,37 @@ :100320004F8FBFF36F8F40F20000C0F2F0004EF627 :100330008851CEF200010860BFF34F8FBFF36F8F7B :100340004FF00000E1EE100A4EF63C71CEF20001D3 -:100350000860062080F31488BFF36F8F06F048F919 -:1003600007F086FA4FF055301F491B4A91423CBFB7 +:100350000860062080F31488BFF36F8F06F054F90D +:1003600007F092FA4FF055301F491B4A91423CBFAB :1003700041F8040BFAE71D49184A91423CBF41F885 :10038000040BFAE71A491B4A1B4B9A423EBF51F82D :10039000040B42F8040BF8E700201849184A914270 -:1003A0003CBF41F8040BFAE706F060F907F0E6FA03 +:1003A0003CBF41F8040BFAE706F06CF907F0F2FAEB :1003B000144C154DAC4203DA54F8041B8847F9E796 :1003C00000F042F8114C124DAC4203DA54F8041B11 -:1003D0008847F9E706F048B900070020002300200D +:1003D0008847F9E706F054B9000700200023002001 :1003E0000000000808ED00E00001002000070020E8 -:1003F00040850008002300206C230020702300208B +:1003F00058850008002300206C2300207023002073 :1004000078740020E0020008E4020008E40200081A :10041000E40200082DE9F04F2DED108AC1F80CD050 :10042000D0F80CD0BDEC108ABDE8F08F002383F328 -:1004300011882846A047002005F0DAFAFEE705F00B -:1004400055FA00DFFEE70000F8B501F0BBF901F056 -:100450005DFB06F029F8074606F0C0F80546A8BB84 +:1004300011882846A047002005F0E6FAFEE705F0FF +:1004400061FA00DFFEE70000F8B501F0BBF901F04A +:100450005DFB06F035F8074606F0CCF80546A8BB6C :100460001F4B9F4232D001339F4232D027F0FF0210 :100470001C4B9A4230D12E4642F21074F8B200F072 :1004800075FF00F079FF08B10024264601F0CEFD8B :1004900020B10024032000F079F8264635B1124B34 -:1004A0009F4203D0002406F091F82646002006F073 -:1004B00005F80EB100F080F801F0C6FA00F090FFE8 +:1004A0009F4203D0002406F09DF82646002006F067 +:1004B00011F80EB100F080F801F0C6FA00F090FFDC :1004C000204600F02BF900F077F8F9E72E460024DB :1004D000D7E704460126D4E7064641F28834D0E740 :1004E000010007B0000008B0263A09B008B501F0D5 :1004F00035F9A0F120035842584108BD07B541F233 :100500001203022101A8ADF8043001F045F903B04F :100510005DF804FB38B5302383F31188174803686E -:100520000BB105F031FB0023154A4FF47A711348E3 -:1005300005F020FB002383F31188124C236813B1CC +:100520000BB105F03DFB0023154A4FF47A711348D7 +:1005300005F02CFB002383F31188124C236813B1C0 :100540002368013B2360636813B16368013B636008 :100550000D4D2B7833B963687BB9022001F0E6F9C1 :10056000322363602B78032B07D163682BB90220F9 @@ -94,7 +94,7 @@ :1005C0004D4B03221A7000224C4B5A60F8BD4C4B25 :1005D0004C4A1C4619680131F8D004339342F9D1D2 :1005E0006268494B9A42F1D9484B9B6803F100631A -:1005F00003F580239A42E9D205F0BCFF05F0CEFF57 +:1005F00003F580239A42E9D205F0C8FF05F0DAFF3F :10060000002001F005F90220FFF7C0FF404B002158 :100610009A6C99641A6F19671A6FDA6CD9645A6FF9 :1006200059675A6F1A6D19659A6F99679B6F394BA5 @@ -115,8 +115,8 @@ :10071000004502580044025800ED00E02DE9F04F7A :1007200093B0B74B2022FF2100900AA89D6801F0EA :1007300035F9B44A1378A3B90121B34811700360A5 -:10074000302383F3118803680BB105F01DFA0023F1 -:10075000AE4A4FF47A71AC4805F00CFA002383F3EB +:10074000302383F3118803680BB105F029FA0023E5 +:10075000AE4A4FF47A71AC4805F018FA002383F3DF :100760001188009B13B1AA4B009A1A60A94A13780A :10077000032B03D000231370A54A53604FF0000AE7 :10078000009CD3465646D146012001F0CDF824B155 @@ -190,11 +190,11 @@ :100BC00049AE00F05FFE002844D00A9B01330BD0F1 :100BD00008220AA9002000F0E9FE00283AD02022CD :100BE000FF210AA800F0DAFEFFF788FC1C4804F099 -:100BF00005FF13B0BDE8F08F002E3FF42BAE0BF0D5 +:100BF00011FF13B0BDE8F08F002E3FF42BAE0BF0C9 :100C00000B030B2B7FF426AE0023642105A805936C :100C100000F0B8FD074600287FF41CAE0220FFF765 :100C200065FC804600283FF415AEFFF767FC41F2F3 -:100C3000883004F0E3FE059800F046FF46463C4647 +:100C3000883004F0EFFE059800F046FF46463C463B :100C400000F0F8FEA0E506464EE64FF0000901E68A :100C5000BA467EE637467CE68C230020002300203F :100C6000A0860100094A49F26900136899B21B0C79 @@ -206,15 +206,15 @@ :100CC0000D466CAC0021204600F068FE02F07EFB71 :100CD0004FF47A72254BB0FBF2F0186093E80700EE :100CE000022384E807000DF5E9702382FFF7D2FFA5 -:100CF00043F204731E4907A8238407F06BF91623F7 +:100CF00043F204731E4907A8238407F077F91623EB :100D00000DF2E3220DF12C0C84F8323107AB1E46B4 :100D1000083203CE664542F8080C42F8041C3346FC :100D2000F5D1306810602046B3880DAE938031460F :100D3000012200F04BFF002380B2E97E0393AB7EDB :100D4000029305F1190301930123009305A3D3E94D -:100D50000023CDE90460384602F044FF0DF54F7DD5 +:100D50000023CDE90460384602F050FF0DF54F7DC9 :100D6000F0BD00BF9E6AC421818A46EE982400200F -:100D7000E47F00082DE9F0412C4CDAB080460D46A6 +:100D7000FC7F00082DE9F0412C4CDAB080460D468E :100D8000237A5BBB27A9284601F044F807460028D0 :100D900042D19DF89D60C82E3ED801464FF4A66210 :100DA000204600F0FBFD4FF4807332460DF19E01AA @@ -224,7 +224,7 @@ :100DE000002127A800F0DAFD0122214627A801F002 :100DF00057F8002380B2E97E0393AB7E029305F19E :100E0000190301932823CDE904400093404605A32C -:100E1000D3E9002302F0E6FE5AB0BDE8F08100BF3E +:100E1000D3E9002302F0F2FE5AB0BDE8F08100BF32 :100E2000AFF3008026417272DF25D7B7E03400208F :100E3000F0B5254E4FF48A75F1B0002405FB00652E :100E400096F8D830D822214685F8DC303AA885F8C3 @@ -233,19 +233,19 @@ :100E7000F100CDE93A3400F06BFD394601223AA881 :100E800001F044F8082380B2317ACDE904700127DB :100E90000E48CDE9023706F1D803019330230093C1 -:100EA00007A3D3E9002302F09DFEA04206DD02F075 +:100EA00007A3D3E9002302F0A9FEA04206DD02F069 :100EB0008DFAC5F8E000384671B0F0BD2046FBE77A :100EC00078F6339F93CACD8DE0340020B0340020F3 :100ED0002DE9F0411D4D86B01D4E1E4F284602F0F3 -:100EE000ADFE034658B30024DFF86C80ADF8144023 +:100EE000B9FE034658B30024DFF86C80ADF8144017 :100EF0000294CDE90344027B8DF8142003AA99687B :100F0000406803C21B6843F00043029302F060FA9A :100F100082190094384641F1000302A901F084FAD5 -:100F2000A04205DD284602F08DFE88F80040D5E796 +:100F2000A04205DD284602F099FE88F80040D5E78A :100F300098F80030072B05D8013388F8003006B048 -:100F4000BDE8F081014802F07DFEF8E7B0340020F2 +:100F4000BDE8F081014802F089FEF8E7B0340020E6 :100F500040420F00183A0020153A002070B50D46A7 -:100F600014461E4602F09AFD50B9022E10D1012CF3 +:100F600014461E4602F0A6FD50B9022E10D1012CE7 :100F70000ED112A3D3E900230120C5E9002307E025 :100F8000282C10D005D8012C09D0052C0FD000201A :100F900070BD302CFBD10BA3D3E90023ECE70BA3EE @@ -260,8 +260,8 @@ :1010200038BD00BFE03400200A4B0B4A10B51A60EF :1010300003F5805393F858203AB95C6D2CB12046E3 :1010400001F072F8204601F0ABF90448BDE8104009 -:1010500001F06AB8183A00208C800008584A002035 -:101060002DE9F04F8FB005460C4600AF02F016FD9B +:1010500001F06AB8183A0020A4800008584A00201D +:101060002DE9F04F8FB005460C4600AF02F022FD8F :1010700000284BD1237E022B1BD1E38A012B18D1F0 :1010800002F0A4F90646FFF7EDFD03464FF4C870E1 :1010900006F51676DFF8D082B3FBF0F202FB1033D0 @@ -269,9 +269,9 @@ :1010B0001A703C37BD46BDE8F08F07F12401204689 :1010C00000F05CFE0028F4D107F11400FFF7E2FD08 :1010D00097F8264007F1140107F12700224606F091 -:1010E00047FF0028E2D10F2C08D8984B1C70D8F885 +:1010E00053FF0028E2D10F2C08D8984B1C70D8F879 :1010F0000030A3F51673C8F80030DAE797F824102B -:101100000029D6D0284602F0C1FCD2E7E38A282B7A +:101100000029D6D0284602F0CDFCD2E7E38A282B6E :1011100033D010D8012B2BD0052BCAD1BFF34F8F62 :101120008B498C4BCA6802F4E0621343CB60BFF377 :101130004F8F00BFFDE7302BBBD1874EE17E327A67 @@ -319,11 +319,11 @@ :1013D0009AAD44C5A424002016000020E03400206B :1013E00037B500F023FE194D022300221849288149 :1013F0006B710123174801F0A7FB002316494FF436 -:1014000080520193154B16480093164B02F016FBC1 -:10141000154B197811B1124802F038FB01F0D6FFD4 +:1014000080520193154B16480093164B02F022FBB5 +:10141000154B197811B1124802F044FB01F0D6FFC8 :101420000446FFF71FFC4FF4C873B0FBF3F202FB56 :10143000130304F5167010FA83F00C4B186005F0D6 -:10144000CDF808B10F232B8103B030BD98240020C4 +:10144000D9F808B10F232B8103B030BD98240020B8 :1014500040420F00183A0020A82400205D0F000829 :10146000B034002061100008A4240020AC34002017 :101470002DE9F04F8C4C2DED028B85A7D7E9006745 @@ -332,7 +332,7 @@ :1014A0000D936B6000234FF0010A0DF1250209A98D :1014B00058468DF825308DF824A08DED008B01F075 :1014C000EDFE9DF824200023002A40F0AE80204647 -:1014D00002F0E4FA0546002847D1DFF8E4B101F054 +:1014D00002F0F0FA0546002847D1DFF8E4B101F048 :1014E00075FFDBF8003098423FD301F06FFF0790A3 :1014F000FFF7B8FB4FF4C873079AB0FBF3F101FB99 :10150000130302F5167010FA83F0CBF8000010A850 @@ -341,23 +341,23 @@ :101530003100C1F110021944D2B2062A28BF062296 :10154000079200F005FA079A0CAB2046039301328C :101550001823D2B20293554B04923246CDE900A330 -:101560003B4602F0E1FA8BF8005001F02FFF504AA1 +:101560003B4602F0EDFA8BF8005001F02FFF504A95 :10157000504D1368C31AB3F57A7F32D3106001F06F -:1015800027FF02460B46204602F066FB204602F08B -:1015900085FA30B32B7A0DF1400BDFF82CA1002B2C +:1015800027FF02460B46204602F072FB204602F07F +:1015900091FA30B32B7A0DF1400BDFF82CA1002B20 :1015A00014BF032302238AF8053001F00FFF4FF424 :1015B0007A7301225946B0FBF3F0CAF80000504696 :1015C00000F0B4FB182380B2424602933A4B0193D9 :1015D00040F25513CDE903B0009320464B4602F08C -:1015E000A3FA2B7AABB101F0F1FE4FF0000A83466B +:1015E000AFFA2B7AABB101F0F1FE4FF0000A83465F :1015F0004FF48A7295F8D900504400F0030002FBC2 :10160000005393F8E81071B30AF1010ABAF1040F1C -:10161000F0D1C82004F0F2F92B7A002B7FF435AF1B +:10161000F0D1C82004F0FEF92B7A002B7FF435AF0F :1016200015B0BDEC028BBDE8F08F1946102210A852 :1016300000F0B4F90DF126030AAA0CA9584601F0EE :1016400015F911AB95E8030083E803009DF83C30E1 :1016500010A920468DF84C300C9B1093DDE90A232D -:1016600002F0CEFC1EE7D3F8E01049B12B68ABEBDB +:1016600002F0DAFC1EE7D3F8E01049B12B68ABEBCF :101670000101FA2B38BFFA230533B1EB430FC3D373 :10168000FFF7D6FB4FF48A720028BDD1C1E700BF37 :10169000401DA12026812A0BF1C6A7C1D068080FE2 @@ -365,13 +365,13 @@ :1016B000103A0020E0340020143A0020183A0020AC :1016C000AC340020A93400209824002008B5054837 :1016D00001F072F9044A05490020BDE8084006F00F -:1016E00033BC00BF183A00203C4F002029100008EE +:1016E0003FBC00BF183A00203C4F002029100008E2 :1016F0002DE9F84F4FF47A7306460D46002402FB9D :1017000003F7DFF85080DFF8509098F900305FFA67 :1017100084FA5A1C01D0A34212D159F824002A4657 :1017200031460368D3F820B03B46D847854207D1FD :10173000074B012083F800A0BDE8F88F0124E4E7FF -:10174000002CFBD04FF4FA7004F058F90020F3E7B6 +:10174000002CFBD04FF4FA7004F064F90020F3E7AA :101750002C4F0020182300201C230020002307B555 :10176000024601210DF107008DF80730FFF7C0FF99 :1017700020B19DF8070003B05DF804FB4FF0FF3087 @@ -379,17 +379,17 @@ :101790000100C0B2404208BD074B0A4630B4197878 :1017A000064B53F82140014623682046DD69044B6F :1017B000AC4630BC604700BF2C4F00201C230020EB -:1017C000A086010070B5104C0025104E04F040FCBE +:1017C000A086010070B5104C0025104E04F04CFCB2 :1017D00020803068238883420CD800252088013877 -:1017E00004F032FC23880544013BB5F5802F2380AB -:1017F000F4D370BD04F028FC336805440133B5F51B +:1017E00004F03EFC23880544013BB5F5802F23809F +:1017F000F4D370BD04F034FC336805440133B5F50F :10180000802F3360E5D3E8E72E4F0020E84E00201C -:1018100004F0ECBC00F1006000F580200068704727 -:1018200000F10060920000F5802004F06DBC000023 +:1018100004F0F8BC00F1006000F58020006870471B +:1018200000F10060920000F5802004F079BC000017 :10183000054B1A68054B1B889B1A834202D910443A -:1018400004F002BC00207047E84E00202E4F00201C -:10185000024B1B68184404F0FDBB00BFE84E00209B -:10186000024B1B68184404F007BC00BFE84E002080 +:1018400004F00EBC00207047E84E00202E4F002010 +:10185000024B1B68184404F009BC00BFE84E00208E +:10186000024B1B68184404F013BC00BFE84E002074 :101870000020704700F1FF5000F58F10D0F80008ED :1018800070470000064991F8243033B10023082244 :10189000086A81F82430FFF7C3BF0120704700BFFA @@ -401,9 +401,9 @@ :1018F0002C2203F8012B0424094A1688AE4204D195 :10190000984284BF967803F8016B013C02F104020F :10191000F3D1581A70BD00BF0010005C24230020D2 -:1019200028800008704700007047000070470000E2 +:1019200040800008704700007047000070470000CA :1019300070B504464FF47A764CB1412C254628BF49 -:10194000412506FB05F0641B04F058F8F4E770BD70 +:10194000412506FB05F0641B04F064F8F4E770BD64 :10195000002310B5934203D0CC5CC4540133F9E7A3 :1019600010BD0000013810B510F9013F3BB191F9ED :1019700000409C4203D11AB10131013AF4E71AB197 @@ -420,104 +420,104 @@ :101A200031FF0028CBD10020BDE8F8830120FBE77F :101A3000EC4E0020024B1A78024B1A70704700BF20 :101A40002C4F00201823002038B51A4C1A4D204680 -:101A500003F0F4FA2946204603F01CFB2D684FF4EE +:101A500003F000FB2946204603F028FB2D684FF4D5 :101A60007A70D5F89020D2F8043843F00203C2F817 -:101A70000438FFF75DFF1149284603F019FCD5F83B +:101A70000438FFF75DFF1149284603F025FCD5F82F :101A800090200F4DD2F80438286823F002030D4946 :101A9000A042C2F804384FF4E1330B6001D003F0E8 -:101AA0002BFA6868A04204D00649BDE8384003F02C -:101AB00023BA38BDA0560020DC820008E48200086A +:101AA00037FA6868A04204D00649BDE8384003F020 +:101AB0002FBA38BDA0560020F4820008FC8200082E :101AC0001C230020144F00200C4B70B50C4D044615 :101AD0001E780C4B55F826209A420DD00A4B002157 :101AE00018221846FFF75AFF0460014655F82600F1 -:101AF000BDE8704003F000BA70BD00BF2C4F00205D +:101AF000BDE8704003F00CBA70BD00BF2C4F002051 :101B00001C230020A0560020144F0020F8B571B609 -:101B1000002301201A46194602F0D6FE0446802012 -:101B200004F002FC002849D00025254A80274FF404 +:101B1000002301201A46194602F0E2FE0446802006 +:101B200004F00EFC002849D00025254A80274FF4F8 :101B3000D06C3D26136913F0C06F26D1D2F8103156 :101B400013F0C06F21D1236805F10061996023680B :101B5000D86023685F602368C3F800C021680B6801 :101B600043F001030B6021680B6823F01E030B6038 :101B700021680B68DB07FCD4237B8035616806FA9B -:101B800003F3B5F5001F0B60D4D1204602F0D2FE5E +:101B800003F3B5F5001F0B60D4D1204602F0DEFE52 :101B9000B5F5001F11D000240A4E0B4D012004F0B2 -:101BA00025FB3388A34205D928682044013404F07A -:101BB00063FAF6E7002004F019FB61B6F8BD00BF38 +:101BA00031FB3388A34205D928682044013404F06E +:101BB0006FFAF6E7002004F025FB61B6F8BD00BF20 :101BC000002000522E4F0020E84E00202DE9F34760 :101BD0000D46044600219046284640F27912FFF750 :101BE000DDFE234620220021284604F1220702F0D0 -:101BF000A9F9231D022220212846C02602F0A2F9BD -:101C0000631D03222221284602F09CF9A31D032212 -:101C10002521284602F096F904F108031022282114 -:101C2000284602F08FF904F11003082238212846D3 -:101C300002F088F904F1110308224021284602F03D -:101C400081F904F1120308224821284602F07AF9AA -:101C500004F1140320225021284602F073F904F104 -:101C6000180340227021284602F06CF904F1200389 -:101C70000822B021284602F065F904F12103082268 -:101C8000B821284602F05EF9314608363B46082264 -:101C90002846013702F056F9B6F5A07FF4D194F842 +:101BF000B5F9231D022220212846C02602F0AEF9A5 +:101C0000631D03222221284602F0A8F9A31D032206 +:101C10002521284602F0A2F904F108031022282108 +:101C2000284602F09BF904F11003082238212846C7 +:101C300002F094F904F1110308224021284602F031 +:101C40008DF904F1120308224821284602F086F992 +:101C500004F1140320225021284602F07FF904F1F8 +:101C6000180340227021284602F078F904F120037D +:101C70000822B021284602F071F904F1210308225C +:101C8000B821284602F06AF9314608363B46082258 +:101C90002846013702F062F9B6F5A07FF4D194F836 :101CA0003230314604F1330A00268DF8073008221D -:101CB0000DF10703284602F045F99DF807304FEA79 +:101CB0000DF10703284602F051F99DF807304FEA6D :101CC000C6099E4209F5A47720D394F83231502BEF :101CD00028BF50238DF80730B8F1000F08D13946DE -:101CE00009F24F170DF107030722284602F02AF9DF +:101CE00009F24F170DF107030722284602F036F9D3 :101CF000002604F233149DF8073007EBC6019E421C :101D00000DD30731C80802B0BDE8F0870AEB06031F -:101D1000082239462846013602F014F9CDE7A31906 -:101D200008222846013602F00DF9E4E713B504460F +:101D1000082239462846013602F020F9CDE7A319FA +:101D200008222846013602F019F9E4E713B5044603 :101D3000084600212022234601900160C0F80310CC -:101D400002F000F9231D01980222202102F0FAF886 -:101D5000631D01980322222102F0F4F8A31D0198CB -:101D60000322252102F0EEF8019804F10803102265 -:101D7000282102F0E7F8072002B010BDF7B5047F74 +:101D400002F00CF9231D01980222202102F006F96D +:101D5000631D01980322222102F000F9A31D0198BE +:101D60000322252102F0FAF8019804F10803102259 +:101D7000282102F0F3F8072002B010BDF7B5047F68 :101D800005460E462CB1838A122B02D9012003B0DE -:101D9000F0BD0023072228460096194601F096FF61 -:101DA000731C0122072100932846002301F08EFFB7 +:101D9000F0BD0023072228460096194601F0A2FF55 +:101DA000731C0122072100932846002301F09AFFAB :101DB000D4B9B31C052208212846009323460D24DC -:101DC00001F084FFB378102BE0D83746BB1BB27804 +:101DC00001F090FFB378102BE0D83746BB1BB278F8 :101DD000934210D307342B7FA88AE408B3B9844216 :101DE00094BF00200120D2E7AB8A0824DB00083B27 :101DF000DB08B370E6E7FB1C214608222846009367 -:101E000000230834013701F061FFDFE7201A18BF13 +:101E000000230834013701F06DFFDFE7201A18BF07 :101E10000120BCE7F7B5047F05460E462CB1838A46 :101E2000CA2B02D9012003B0F0BD002308222846A6 -:101E30000096194601F04AFF731CD4B9082200939A -:101E4000234610241146284601F040FF7378C82B22 +:101E30000096194601F056FF731CD4B9082200938E +:101E4000234610241146284601F04CFF7378C82B16 :101E5000E8D801235F1C7278013B934210D307340A :101E60002B7FA88AE408B3B9844294BF00200120E4 :101E7000D9E7AB8A0824DB00083BDB087370E5E791 -:101E8000F3192146082228460093002301F01EFF83 +:101E8000F3192146082228460093002301F02AFF77 :101E900008343B46DEE7201A18BF0120C3E70000E4 :101EA000F7B50D4604460021164628468122FFF765 -:101EB00075FD234608220021284602F043F894F9D4 +:101EB00075FD234608220021284602F04FF894F9C8 :101EC00001206378002AB8BF7F238DF807309EB9C0 -:101ED0000F270DF1070307220821284602F032F8E8 +:101ED0000F270DF1070307220821284602F03EF8DC :101EE000002602349DF8073007EBC6019E4205D359 :101EF0000731C80803B0F0BD0827F1E7A31908228D -:101F00002846013602F01EF8ECE70000F7B50E4651 +:101F00002846013602F02AF8ECE70000F7B50E4645 :101F10000546002114463046CE22FFF73FFD2B46F2 -:101F200028220021304602F00DF82B7AC82B28BF5A +:101F200028220021304602F019F82B7AC82B28BF4E :101F3000C8238DF807308CB930240DF1070308222F -:101F40002821304601F0FEFF2F467B1B9DF807201D +:101F40002821304602F00AF82F467B1B9DF8072017 :101F5000934205D3E01DC00803B0F0BD2824F3E789 :101F600007F109032146082230460834013701F001 -:101F7000E9FFEAE7F7B5047F05460E4634B1838AE8 +:101F7000F5FFEAE7F7B5047F05460E4634B1838ADC :101F8000B3F5827F02D9012003B0F0BD01231022F6 -:101F900000212846009601F099FEDCB9B31C092205 -:101FA0001021284600932346192401F08FFE7388E0 +:101F900000212846009601F0A5FEDCB9B31C0922F9 +:101FA0001021284600932346192401F09BFE7388D4 :101FB000B3F5807FE7D83746BB1B7288934210D3B6 :101FC00007342B7FA88AE408B3B9844294BF002069 :101FD0000120D9E7AB8A1024DB00103BDB087380BB :101FE000E5E73B1D214608222846009300230834DC -:101FF000013701F06BFEDFE7201A18BF0120C3E7AD +:101FF000013701F077FEDFE7201A18BF0120C3E7A1 :1020000030B50A44084D91420DD011F8013B5840BB :10201000082340F30004013B2C4013F0FF0384EA43 :102020005000F6D1EFE730BD2083B8EDF7B5384A60 :102030006B46106851686A4603C308233549364821 -:1020400005F0A6FF0446002833D10A25334A6B4623 +:1020400005F0B2FF0446002833D10A25334A6B4617 :10205000106851686A4603C3082331492E4805F0C9 -:1020600097FF0446002849D00369B3F5E01F45D81F +:10206000A3FF0446002849D00369B3F5E01F45D813 :10207000B0F8661040F2374291423FD1294A0244FB :1020800002F15C018B4239D35C3B234900209E1A4C :10209000FFF7B6FF04F16401074632460020FFF760 @@ -528,9 +528,9 @@ :1020E00006462A460020FFF78BFFA3689E4202D1D6 :1020F000E368984201D00D25A8E70025284603B0E3 :10210000F0BD1025A2E70C25A0E70B259EE700BF38 -:1021100038800008DCFF1B00000004084180000834 +:1021100050800008DCFF1B00000004085980000804 :1021200090FF1B000800FCF710B5037C044613B9B0 -:10213000006804F02DF9204610BD00000023BFF315 +:10213000006804F039F9204610BD00000023BFF309 :102140005B8FC360BFF35B8FBFF35B8F8360BFF3B5 :102150005B8F7047BFF35B8F0068BFF35B8F704787 :1021600070B505460C30FFF7F5FF044605F108068B @@ -569,7 +569,7 @@ :1023700054F8081B42464644FFF7EAFAF3E73046B2 :1023800004B0BDE8F081000038B50546FFF7E0FF76 :10239000044601462846FFF717FF204638BD0000D7 -:1023A00008B103F0F5BF70477047000010B4134642 +:1023A00008B104F001B870477047000010B413463C :1023B000026814680022A4465DF8044B60470000E0 :1023C00000F5805090F869047047000000F58050D7 :1023D00090F862047047000000F5805090F968049E @@ -584,7 +584,7 @@ :102460000133C1F88C344FF0FF30A9E0302080F305 :102470001188E86BD0F8C47017F4001713D0D1F8A6 :1024800090040130C1F89004D1F89414002940F070 -:102490009A8021462846CDF8008000F0E1FF002315 +:102490009A8021462846CDF8008000F0E7FF00230F :1024A00083F311888CE0D0F8C4604FF04809686B62 :1024B000C6F3044619FB060920684FEA461A0028AD :1024C000B4BF40F0804C4FEA804CC9F800C020688F @@ -592,7 +592,7 @@ :1024E0000CC040EA0C40C9F8040094F80DC0BCF1DF :1024F000000F26D040F44010C9F80400D1F8C00401 :102500000130C1F8C00405EB0A0101F58351087FD1 -:1025100040F020000877207BCDE9022300F0F2FF95 +:1025100040F020000877207BCDE9022300F0FEFF89 :102520000330DDE902238010F9B20137814210DA6D :1025300004EB810C09EB8101DCF804C0C1F808C090 :10254000F2E705EB0A0101F58351087F6CF34510B2 @@ -602,7 +602,7 @@ :1025800004CBF9D10088AA44088041F278014AF8C6 :1025900001600AF5805A08F003019AF87C0041F0C6 :1025A000100120F01F0001438AF87C10002181F304 -:1025B000118821462846CDF8008000F051FF012007 +:1025B000118821462846CDF8008000F057FF012001 :1025C00004B0BDE8F087002069E700002DE9F0477E :1025D00000F58056044696F86254002D40F00481C0 :1025E00090F82030032B40F0948028462B462F464D @@ -638,7 +638,7 @@ :1027C00023F00103936100F001FE0746E36B9B6970 :1027D000DB0705D500F0FAFDC31BFA2BF6D995E708 :1027E000012586F8625491E7002592E7384F0020D2 -:1027F000FCB500404C8000080000FF0713B500F551 +:1027F000FCB50040648000080000FF0713B500F539 :1028000080540191606DFFF7C5FC1F280AD9202272 :102810000199606DFFF734FDA0F120035842584143 :1028200002B010BD0020FBE708B5302383F3118808 @@ -665,8 +665,8 @@ :1029700084F86884A4F86A54A4F86C54A4F86E54DB :1029800084F87054A4F87254A4F87454A4F87654DB :1029900084F87854B8F1000F02D0054800F010FD1B -:1029A000044B3046F363BDE8F88F00BF8C8000080D -:1029B0007080000800A00040044B10B51978044650 +:1029A000044B3046F363BDE8F88F00BFA4800008F5 +:1029B0008880000800A00040044B10B51978044638 :1029C0004A1C1A70FFF79CFF204610BD354F0020AF :1029D0002DE9F04300295AD02E4E2F48B6FBF1F4D2 :1029E00081428CBF0A201120431EB4FBF0F700FB8C @@ -684,14 +684,14 @@ :102AA00005200D4D1C786C438C420ED159780120C5 :102AB000518099785171D9789171197911715B7937 :102AC00003EB83035B00138030BD013803F1060381 -:102AD000E8D1F9E7D080000840420F0038B540F255 +:102AD000E8D1F9E7E880000840420F0038B540F23D :102AE0007772C36B154CC3F8BC200722C36BC3F8C5 :102AF000C8202268C16B930043F4C023C1F8A03002 :102B000002F1805302F16C01C56B03F52C53EA32DC :102B100089009B00226041F0E061094AC362C5F868 :102B2000C01003F5D87103F56A7341639342836360 :102B300002D9044800F044FC38BD00BF384F0020E3 -:102B4000FCB500404C8000082DE9F04700F58055A9 +:102B4000FCB50040648000082DE9F04700F5805591 :102B50001F4688B0044695F8683489469046012B94 :102B600004D90026304608B0BDE8F0879F4A52F8E5 :102B7000231009B942F823009D48C4F81C9001783D @@ -699,8 +699,8 @@ :102B9000EC2042F48072C3F8EC20D3F8942042F485 :102BA0008072C3F89420D3F8942022F48072C3F882 :102BB00094200123037081F3118895F861647EB934 -:102BC000302383F311880321132001F0C9FF03216F -:102BD000152001F0C5FF012385F8613486F31188C3 +:102BC000302383F311880321132001F0D5FF032163 +:102BD000152001F0D1FF012385F8613486F31188B7 :102BE000302383F31188E26B936923F01003936120 :102BF00000F0ECFB8246E36B9E6916F0080609D0F4 :102C000000F0E4FBA0EB0A03FA2BF4D9002686F3CC @@ -759,7 +759,7 @@ :102F50000043920048BF43F080430093736813F42A :102F600000131BBF012304F580528DF80D308DF83E :102F70000D301EBFD2F8C8340133C2F8C834F3880C -:102F800003F00F038DF80C309DF80C0000F0BAFA36 +:102F800003F00F038DF80C309DF80C0000F0C6FA2A :102F90005FFA8BF3984225D9F2180CA90BF1010BBB :102FA000127A0B4403F82C2CEEE7012FA7D1E36B28 :102FB000D3F8B02012F4FE0FA1D0D3F8B4209501BD @@ -821,1321 +821,1323 @@ :103330002B7813B1BBF1000FDAD1337813B1019BB5 :10334000002BD5D100F044F804460F46DCE70020FE :10335000CFE7000008B50020FFF7C2FEBDE8084037 -:1033600001F0A8B808B50120FFF7BAFEBDE8084093 -:1033700001F0A0B800B59BB0EFF309816822684660 +:1033600001F0B4B808B50120FFF7BAFEBDE8084087 +:1033700001F0ACB800B59BB0EFF309816822684654 :10338000FEF7E6FAEFF30583014B9B6BFEE700BF08 :1033900000ED00E008B5FFF7EDFF000000B59BB0C1 :1033A000EFF3098168226846FEF7D2FAEFF305834E :1033B000014B5B6BFEE700BF00ED00E0FEE70000A5 -:1033C0000FB408B5029802F0BFFAFEE703F00EB89A -:1033D00002F0F0BF0139C9B202299EBF00EBC10063 -:1033E0000023C0E901337047F8B51B8805460E4637 -:1033F0005B0715D4044600F11807BC4210D063687F -:1034000053B12B682846DB6B9847A368C1B232469C -:10341000606898470834F0E7A368002BF1D1F9E71A -:103420000120F8BD73B56C4684E806000146002211 -:103430004E68D5B26EB98E685EB900EBC200013538 -:10344000021D94E8030082E8030001201D7002B011 -:1034500070BD01320831032AEAD10020F7E70000ED -:103460002DE9F04F89B004460E460546BDF8487078 -:1034700000F118084FF000094FF0000A07F00407A8 -:103480004FF0000BA84539D06B680BB9AB684BB156 -:1034900057B923682046DB6B9847AB68C1B2324608 -:1034A000686898470835EDE7B9F1000FFAD133465F -:1034B00003AA06F1080EADF80890CDE900AB186834 -:1034C000083353F8041C94467345ACE80300624685 -:1034D000F5D118684FF00109CCF800009B88ACF8D2 -:1034E0000430FFF775FF0423ADF808302368CDE9F9 -:1034F00000011B6C694620469847D3E7012009B0BC -:10350000BDE8F08F082817D909280CD00A280CD05C -:103510000B280CD00C280CD00D280CD00E2814BF72 -:103520004020302070470C20704710207047142036 -:103530007047182070472020704700002DE9F041A7 -:10354000456A15B94162BDE8F0814B68AC4623F08D -:103550006047C3F38A464FEAD37EC3F3807816EA06 -:10356000230638BF3E462B465A68BEEBD27F22F078 -:1035700060440AD0002A18DAA40CB44217D19D4244 -:103580000FD10D60DEE71346EEE7A74207D102F048 -:103590008044C2F3807242450BD054B1EFE708D2A9 -:1035A000EDE7CCF800100B60CDE7B44201D0B44297 -:1035B000E5D81A689C46002AE5D11960C3E70000E7 -:1035C0002DE9F047089D01F0070400EBD1004FF40E -:1035D0007F494FEAD508224405F00705944201D1FE -:1035E000BDE8F08704F0070705F0070A111B08EB98 -:1035F000D50E57453E4613F80EC038BF5646C6F1A5 -:1036000008068E4228BF0E46E108415C344435442A -:10361000B94029FA06F721FA0AF1FFB28CEA010152 -:1036200047FA0AF739408CEA010C03F80EC0D5E7D7 -:1036300080EA0120082341F2210201B2013B40004F -:10364000002980B2B8BF504013F0FF03F5D1704796 -:1036500038B50C468D18A54200D138BD14F8011BB1 -:10366000FFF7E6FFF7E7000042684AB11368818977 -:103670004360438901339BB29942438138BF8381C0 -:103680001046704770B588B0044620220D46684643 -:103690000021FEF783F920460495FFF7E5FF024677 -:1036A00060B16B46054608AE1C46083503CCB442F3 -:1036B00045F8080C45F8041C2346F5D1104608B01F -:1036C00070BD0000082817D909280CD00A280CD092 -:1036D0000B280CD00C280CD00D280CD00E2814BFB1 -:1036E0004020302070470C20704710207047142075 -:1036F000704718207047202070470000082817D90D -:103700000C280CD910280CD914280CD918280CD93D -:1037100020280CD930288CBF0F200E20704709209C -:1037200070470A2070470B2070470C2070470D200F -:10373000704700002DE9F843078C0446072F1ED977 -:1037400000254FF6FF73D0E90298C5F12006A5F1D8 -:10375000200029FA05F1083508FA06F628FA00F0E3 -:10376000314301431846C9B2FFF762FF402D0346BB -:10377000EBD13A46E169BDE8F843FFF769BF4FF680 -:10378000FF70BDE8F883000010B54B6823B9CA8A02 -:1037900063F30902CA8210BD04691A681C600361E0 -:1037A000C38A013BC3824A60EFE700002DE9F84F6E -:1037B0001D46CB8A0F468146C3F30901924605296F -:1037C0000B4630D00020AAB207F11A049EB21FFAAD -:1037D00080F8042E0FD8904503F1010306D30A4464 -:1037E000FB8A62F309030120FB821AE01AF80060E9 -:1037F0000130E654EAE79045F1D2A1F1050B1C2314 -:103800007C68BBFBF3F203FB12BB1FFA8BF6002CA8 -:1038100045D14846FFF728FF044638B978606FF075 -:103820000200BDE8F88F4FF00008E6E700260660CA -:103830007860ADB24FF0000B454510D90AEB080394 -:10384000221D13F8011B08F101089155B1B21FFAAE -:1038500088F81B292BD0454506F10106F1D8FB8AD3 -:10386000C3F30902154465F30903BCE701321C46A2 -:1038700092B22368002BF9D16B1F0B441C21B3FBC0 -:10388000F1F301339BB29A42D3D2BBF1000FD0D1F6 -:103890004846FFF7E9FE20B9C4F800B0BFE70122AF -:1038A000E7E7C0F800B05E4620600446C1E7454542 -:1038B000D5D94846FFF7D8FE08B92060AFE7C0F871 -:1038C00000B0002620600446B6E700002DE9F04F66 -:1038D0001C46074688462DED028B83B05B6901923A -:1038E000002B00F0A780238C2BB1E269002A00F0A6 -:1038F000A180072B35D807F10C00FFF7B5FE054670 -:1039000038B96FF00205284603B0BDEC028BBDE864 -:10391000F08F14220021FEF741F8228CE16905F1B5 -:103920000800FEF715F8208C48F00041013080B205 -:10393000FFF7E4FEFFF7C6FE013880B220840130B5 -:10394000287438466369228C1B782A4403F01F03CD -:1039500063F03F03137269602946FFF7EFFD01250D -:10396000D1E702330722C18A9BB20633B3FBF2F3DD -:10397000828A9BB2521A92B29342C2D84FF0000987 -:1039800000F10C034FF0800A4E464D4608EE103A07 -:1039900018EE100AFFF768FE83460028B1D0142203 -:1039A0000021FDF7FBFF002E3AD1019B0222ABF86C -:1039B00008300BF1080E1FFA82FC218C0CF101007B -:1039C000BCF1060F80B201D88E422BD3FFF796FED2 -:1039D0008E4208BF4FF0400AFFF774FE626901385B -:1039E000013512781BFA80F1013002F01F022DB26E -:1039F00042EA491289F001094AEA020A48F0004203 -:103A000081F808A059468BF810003846CBF80420FE -:103A10004FF0000AFFF792FD238CB342B8D172E752 -:103A20000022C6E7E169895D01360EF80210B6B2E0 -:103A30000132C0E76FF0010565E70000F8B51546F3 -:103A40000E463022002104461F46FDF7A7FF069BC5 -:103A5000B5F5001FA760636004F11000079B34BF39 -:103A60006A094FF6FF72E661A362002397B29A4299 -:103A700006D800230360A782E3822383E360F8BDB6 -:103A80000660013330462036F1E7000003781BB9A9 -:103A90004BB2002BC8BF0170704700000078704720 -:103AA000F8B50C46C969074611B9238C002B37D1EC -:103AB000257E1F2D34D8387828BB228C072A2CD895 -:103AC000268A36F003032BD14FF6FF70FFF7C0FDB7 -:103AD00020F0010031024FF6FF72400441EA056117 -:103AE000400C41EA4025234629463846FFF7EEFEC2 -:103AF000002807DD626913780133DBB21F2B88BF12 -:103B000000231370F8BD218A2D0645EA01250543DF -:103B10002046FFF70FFE0246E5E76FF00300F1E7EE -:103B20006FF00100EEE7000070B58AB0044616465B -:103B30000021282268461D46FDF730FFBDF83830C9 -:103B400069462046ADF810300F9B05939DF8403034 -:103B50008DF81830119B0793BDF84830CDE9026508 -:103B6000ADF82030FFF79CFF0AB070BD2DE9F041A1 -:103B7000D36905460C4616460BB9138C5BBB377EE2 -:103B80001F2F28D895F80080B8F1000F26D03046B6 -:103B9000FFF7D0FD337821020246284641EAC331BF -:103BA000338A41EA080141EA076141EA03413346A9 -:103BB00041F08001FFF78AFE00280ADD3378012BEF -:103BC00007D1726913780133DBB21F2B88BF002342 -:103BD0001370BDE8F0816FF00100FAE76FF00300A9 -:103BE000F7E70000F0B58BB004460D4617460021FC -:103BF000282268461E46FDF7D1FE9DF84C30294626 -:103C000020465A1E534253416A468DF800309DF8B3 -:103C10004030ADF81030119B05939DF848308DF879 -:103C20001830149B0793BDF85430CDE90276ADF8F7 -:103C30002030FFF79BFF0BB0F0BD0000406A00B1E1 -:103C400004307047436A1A68426202691A6003616D -:103C5000C38A013BC38270472DE9F041D0F8208030 -:103C600014461D46184E4146002709B9BDE8F081AB -:103C7000D1E90223A21A65EB0303964277EB030313 -:103C80001ED2036A8B420DD1FFF77EFD036A1B68CB -:103C9000036203690B60C38A0161013B016AC3824D -:103CA0008846E2E7FFF770FD0B68C8F8003003694B -:103CB0000B60C38A0161013BC382D8F80010D4E7CE -:103CC00088460968D1E700BF80841E002DE9F04FC7 -:103CD0008BB00D4614469B46DDF850908046002878 -:103CE00000F01881B9F1000F00F01481531E3F2B32 -:103CF00000F21081012A03D1BBF1000F40F00A81CC -:103D00000023CDE90833B8F81430B5EBC30F4FEA00 -:103D1000C30703D300200BB0BDE8F08F2B199F42DF -:103D2000D8F80C3036BF7F1B2746FFB21BB9D8F836 -:103D30001030002B7AD0272D4DD8C5F1280600234E -:103D40002946B742009308ABD8F808002CBFF6B25A -:103D50003E46A7EB060A354432465FFA8AFAFFF779 -:103D60002FFCB8F81430282103F10053053BDB0089 -:103D70000493D8F80C300393039B13B1BAF1000FEE -:103D80002CD1D8F8100040B1BAF1000F05D008AB23 -:103D90005246691A0096FFF713FC38B2002FB9D0CB -:103DA00066070AD00AAB624203EBD40102F00702B5 -:103DB00011F8083C134101F8083C082C3DD9102C9F -:103DC00040F2B580202C40F2B780BBF1000F00F02C -:103DD0009C80082335E0BA460026C2E7049BE02B0E -:103DE00028BFE02306930B44AB42059315D95A1B19 -:103DF0000398691A0096924508AB00F1040034BF9D -:103E00005246D2B20792FFF7DBFB079A1644AAEBA1 -:103E1000020A1544F6B25FFA8AFA049B069A0599DB -:103E20009B1A0493039B1B680393A5E700933A46F0 -:103E300008AB2946D8F80800ADE7BBF1000F13D056 -:103E40000123B4EBC30F6BD0082C12D89DF820309F -:103E5000621E23FA02F2D50706D54FF0FF3202FAAE -:103E600004F423438DF820309DF8203089F8003089 -:103E700051E7102C12D8BDF82030621E23FA02F24E -:103E8000D10706D54FF0FF3202FA04F42343ADF810 -:103E90002030BDF82030A9F800303CE7202C0FD8A6 -:103EA0000899631E21FA03F3DA0705D54FF0FF32B4 -:103EB00002FA04F40C430894089BC9F800302AE77E -:103EC000402C2AD0611EC4F12102A4F12103DDE9B6 -:103ED000086526FA01F105FA02F225FA03F3114307 -:103EE0001943CB0711D50122A4F12003C4F120010D -:103EF00002FA03F322FA01F1A2400B43524263EBB0 -:103F0000430332432B43CDE90823DDE90823C9E904 -:103F1000002300E76FF00100FDE66FF00800FAE60D -:103F2000082CA1D9102CB4D9202CEED8C4E7BBF1B1 -:103F3000000FAED0022384E7BBF1000FBCD00423F6 -:103F40007FE70000012A30B5144638BF012485B050 -:103F50000025402C28BF4024012ACDE9025518D85D -:103F60001B788DF8083063070AD004AB624203EB7C -:103F7000D40502F0070215F8083C934005F8083C08 -:103F8000034600912246002102A8FFF719FB05B065 -:103F900030BD082AE4D9102A03D81B88ADF80830B0 -:103FA000E1E7202A95BF1B68D3E900230293CDE9FE -:103FB0000223D8E710B5CB681BB98B600B618B82ED -:103FC00010BD04691A681C600361C38A013BC38287 -:103FD000CA60F0E703064CBFC0F3C0300220704750 -:103FE00008B50246FFF7F6FF022806D15306C2F3D2 -:103FF0000F2001D100F0030008BDC2F30740FBE72A -:104000002DE9F04F93B004460D46CDE903230A682D -:104010001046FFF7DFFF0228824614BFC2F30626D0 -:104020000026002A80F2F88112F0C04940F0F481A5 -:10403000097B002900F0F081022803D02378B342E5 -:1040400040F0ED81C2F3046310462944069302F068 -:104050007F030593FFF7C4FF059B002283464FEAC9 -:104060008348002348EA0A4848EA4668CE78CDE902 -:104070000823F30948EA0008029368D0059B02462A -:1040800008A92046009353466768B847002800F007 -:10409000C981276A4FB9414604F10C00FFF7F2FAD3 -:1040A000074690B96FF0020055E03B6998450DD086 -:1040B0003F68002FF9D1414604F10C00FFF7E2FA06 -:1040C00007460028EED0236A3B60276297F817C0A6 -:1040D00006F01F08CCF3840CACEB0800A8EB0C0333 -:1040E0001FFA80FE0028B8BF0EF120001FFA83FEE1 -:1040F000B8BF00B2002B0793B8BF0EF12003D7E979 -:104100000221BCBF1BB2079352EA010338D0039BC4 -:104110004FF0000CDFF81CE39A1A049B63EB0101DB -:1041200096457CEB01032BD36B7B97F81AE0734524 -:1041300019D1029B002B78D0012821DC7868F8B9CE -:10414000DFF8ECC2944570EB010316D337E0276A21 -:1041500027B96FF00C0013B0BDE8F08F3B699845AC -:10416000B4D03F68F4E7B24890427CEB010301D33E -:104170000020F0E7029B002BFAD0079B0F2B17DCE7 -:10418000FA7DB3003946204602F0030203F07C03B7 -:104190001343FB75FFF7F8FA6B7BBB76029B3BB9C9 -:1041A000FB7DC3F38402013262F38603FB75D0E723 -:1041B0006A7BBB7E9A42DBD1029B002B35D0B309D0 -:1041C000022B32D0039B142200210DA8BB60049B5C -:1041D000FB60FDF7E3FB039B0AA920460A93049BBF -:1041E000ADF83EB00B932B1D8DF840A00C932B7BAC -:1041F0008DF84180013BDBB2ADF83C30069B8DF879 -:104200004230059B8DF8433094F82C3083F0010345 -:104210008DF84430A3689847FB7DC3F384030133D2 -:1042200003F01F039B02FB82A2E7FB7DC6F3401253 -:10423000B2EBD31F40F0F980C3F38403434540F051 -:10424000FB80029AB6092B7B002A52D016F0010699 -:1042500061D1032B40F2F380039B394604F10C003B -:10426000BB60049BFB60FB8A66F30903AE1DFB8207 -:1042700032462B7B033BDBB2FFF798FA00280CDABF -:1042800039462046FFF780FAFB7DC3F384030133F0 -:1042900003F01F039B02FB8204E7AB88DDE908847F -:1042A0003B834FF6FF73C9F12000A9F1200228FAE1 -:1042B00009F109F1080904FA00F024FA02F20143B5 -:1042C00018461143C9B2FFF7B3F9B9F1400F0346DD -:1042D000E9D1B88231462A7B033AD2B2FFF7B8F966 -:1042E000FB7DB882DA43C2F3C01262F3C713FB75D9 -:1042F0003EE786B92E1D013B394604F10C00DBB2C6 -:104300003246FFF753FA0028BADB2A7B3146B88AD7 -:10431000013AD2B2E2E7F98A013BC1F30901DAB20C -:1043200004295BD8281D002307F11B069A4208D9EF -:1043300010F801CB013306F801C00131DBB20529C9 -:10434000F4D1039993420A9138BF043304992CBFE6 -:10435000002355FA83F30B9107F11B010C91796847 -:104360000E930D91291DFB8AADF83EB0C3F30903EE -:104370008DF840A08DF841801A44069B8DF842309C -:10438000059BADF83C208DF8433094F82C3083F039 -:1043900001038DF844300023B88A7B602A7B013A00 -:1043A000FFF756F93B8BB882834203D1A3680AA971 -:1043B0002046984720460AA9FFF7FCFDFB7DBA8AF4 -:1043C000C3F38403013303F01F039B02FB823B8B87 -:1043D0009A420CBF00206FF01000BCE67B68002BF7 -:1043E000AFD0052001E01C3033461E68002EFAD104 -:1043F000091A2E1D081D184401EB090C5FFA89F3F8 -:10440000BCF11B0F9DD89A429BD916F8013B09F1CC -:10441000010900F8013BEFE76FF009009BE66FF040 -:104420000A0098E66FF00B0095E66FF00D0092E63B -:1044300040420F0080841E006FF00E008BE66FF08C -:104440000F0088E6EFF30983054968334A6B22F0D1 -:1044500001024A6383F30988002383F311887047BC -:1044600000EF00E0302080F3118862B60D4B0E4A59 -:10447000D96821F4E0610904090C0A430B49DA60A8 -:10448000D3F8FC2042F08072C3F8FC20084AC2F83E -:10449000B01F116841F0010111602022DA7783F822 -:1044A0002200704700ED00E00003FA0555CEACC5D0 -:1044B000001000E0302310B583F311880E4B5B68C9 -:1044C00013F4006314D0F1EE103AEFF309844FF0C7 -:1044D0008073683CE361094BDB6B236684F30988D6 -:1044E00001F0F8F910B1064BA36110BD054BFBE7D5 -:1044F00083F31188F9E700BF00ED00E000EF00E072 -:104500003F0400084204000808B5074B074A196831 -:1045100001F03D01996053680BB190689847BDE880 -:104520000840FFF7C7BF00BF00000240404F002017 -:1045300008B5084B1968890901F03D018A019A60A4 -:10454000054AD3680BB110699847BDE80840FFF7EA -:10455000B1BF00BF00000240404F002008B5084B2B -:104560001968090C01F03D010A049A60054A536973 -:104570000BB190699847BDE80840FFF79BBF00BFAB -:1045800000000240404F002008B5084B1968890D13 -:1045900001F03D018A059A60054AD3690BB1106AA2 -:1045A0009847BDE80840FFF785BF00BF0000024004 -:1045B000404F002008B5074B074A596801F03D01FC -:1045C000D960536A0BB1906A9847BDE80840FFF77D -:1045D00071BF00BF00000240404F002008B5084BEB -:1045E0005968890901F03D018A01DA60054AD36AF8 -:1045F0000BB1106B9847BDE80840FFF75BBF00BFE9 -:1046000000000240404F002008B5084B5968090CD3 -:1046100001F03D010A04DA60054A536B0BB1906B5F -:104620009847BDE80840FFF745BF00BF00000240C3 -:10463000404F002008B5084B5968890D01F03D0135 -:104640008A05DA60054AD36B0BB1106C9847BDE858 -:104650000840FFF72FBF00BF00000240404F00207E -:1046600008B5074B074A196801F03D019960536C82 -:104670000BB1906C9847BDE80840FFF71BBF00BF27 -:1046800000040240404F002008B5084B1968890912 -:1046900001F03D018A019A60054AD36C0BB1106D9F -:1046A0009847BDE80840FFF705BF00BF000402407F -:1046B000404F002008B5084B1968090C01F03D0176 -:1046C0000A049A60054A536D0BB1906D9847BDE896 -:1046D0000840FFF7EFBE00BF00040240404F00203B -:1046E00008B5084B1968890D01F03D018A059A60EB -:1046F000054AD36D0BB1106E9847BDE80840FFF72F -:10470000D9BE00BF00040240404F002008B5074B4F -:10471000074A596801F03D01D960536E0BB1906EA4 -:104720009847BDE80840FFF7C5BE00BF000402403F -:10473000404F002008B5084B5968890901F03D0138 -:104740008A01DA60054AD36E0BB1106F9847BDE855 -:104750000840FFF7AFBE00BF00040240404F0020FA -:1047600008B5084B5968090C01F03D010A04DA60EC -:10477000054A536F0BB1906F9847BDE80840FFF7AB -:1047800099BE00BF00040240404F002008B5084B0E -:104790005968890D01F03D018A05DA60054AD36F39 -:1047A00013B1D2F880009847BDE80840FFF782BEF9 -:1047B00000040240404F002000230C4910B51A4667 -:1047C0000B4C0B6054F82300026001EB43000433F0 -:1047D0004260402BF6D1074A4FF0FF339360D3601D -:1047E000C2F80834C2F80C3410BD00BF404F00209E -:1047F000F0800008000002400F28F8B510D91028FA -:1048000010D0112811D0122808D10F240720DFF86A -:10481000B4E00126DEF80050A04208D9002649E0A5 -:104820000446F4E70F240020F1E70724FBE706FA2B -:1048300000F73D4240D1214C4FEA001C3D4304EBC0 -:1048400000160EEBC000CEF80050C0E90123FBB209 -:104850004BB11B48836B43F001038363036E43F04A -:1048600001030366036E17F47F4F09D01448836B6E -:1048700043F002038363036E43F002030366036E97 -:1048800054F80C00036823F01F030360056815F05B -:104890000105FBD104EB0C033D2493F80CC05F68C9 -:1048A00004FA0CF43C6021240560446112B1987B49 -:1048B00000F056F93046F8BD0130ADE7F080000851 -:1048C00000450258404F002010B5302484F3118871 -:1048D000FFF792FF002383F3118810BD10B5044643 -:1048E000807B00F053F901231049627B03FA02F246 -:1048F0000B6823EA0203DAB20B604AB90C4A916BE7 -:1049000021F001019163116E21F001011166126E17 -:1049100013F47F4F09D1064B9A6B22F002029A637F -:104920001A6E22F002021A661B6E10BD404F002064 -:104930000045025808B5302383F31188FFF7CEFFF6 -:10494000002383F3118808BD0268436811430160A6 -:1049500003B1184770470000024A136843F0C003D0 -:10496000136070470078004013B50E4C204600F0ED -:10497000B7FA04F1140000234FF400720A490094BE -:1049800000F074F9094B4FF40072094904F1380042 -:10499000009400F0EDF9074A074BC4E9172302B071 -:1049A00010BD00BFC44F00203050002059490008FE -:1049B000305200200078004000E1F505037C30B55E -:1049C000214C002918BF0C46012B0CD11F4B9842DB -:1049D00009D11F4B9A6C42F080429A641A6F42F0E0 -:1049E00080421A671B6F2268036EC16D03EB52038E -:1049F0008466B3FBF2F36268150442BF23F0070537 -:104A000003F0070343EA4503CB60A36843F0400388 -:104A10004B60E36843F001038B6042F4967343F00C -:104A200001030B604FF0FF330B62510505D512F007 -:104A3000102205D0B2F1805F04D080F8643030BD20 -:104A40007F23FAE73F23F8E7F0810008C44F0020F6 -:104A5000004502582DE9F047C66D05463768F469F0 -:104A6000210734621AD014F0080118BF4FF4807186 -:104A7000E20748BF41F02001A3074FF0300348BFD1 -:104A800041F04001600748BF41F0800183F3118885 -:104A9000281DFFF759FF002383F31188E2050AD58B -:104AA000302383F311884FF48061281DFFF74CFFFA -:104AB000002383F311884FF030094FF0000A14F0FF -:104AC000200838D13B0616D54FF0300905F1380AD9 -:104AD000200610D589F31188504600F07DF9002892 -:104AE00036DA0821281DFFF72FFF27F080033360F7 -:104AF000002383F31188790614D5620612D530237A -:104B000083F31188D5E913239A4208D12B6C33B172 -:104B100027F040071021281DFFF716FF37600023FC -:104B200083F31188E30618D5AA6E1369ABB15069F7 -:104B3000BDE8F047184789F31188736A284695F84D -:104B40006410194000F0E6F98AF31188F469B6E7B9 -:104B5000B06288F31188F469BAE7BDE8F087000015 -:104B6000090100F16043012203F56143C9B283F8F2 -:104B7000001300F01F039A4043099B0003F16043B8 -:104B800003F56143C3F880211A60704700F01F03EA -:104B900001229A40430900F160409B0000F561400A -:104BA00003F1604303F56143C3F88020C3F880211B -:104BB000002380F800337047F8B515468268044634 -:104BC0000B46AA4200D28568A1692669761AB542C9 -:104BD0000BD218462A46FCF7BBFEA3692B44A361FF -:104BE0002846A3685B1BA360F8BD0CD9AF1B184611 -:104BF0003246FCF7ADFE3A46E1683044FCF7A8FEC9 -:104C0000E3683B44EBE718462A46FCF7A1FEE3685D -:104C1000E5E7000083689342F7B50446154600D2E5 -:104C20008568D4E90460361AB5420BD22A46FCF7EF -:104C30008FFE63692B4463612846A3685B1BA360F6 -:104C400003B0F0BD0DD93246AF1B0191FCF780FED9 -:104C500001993A46E0683144FCF77AFEE3683B4448 -:104C6000E9E72A46FCF774FEE368E4E710B50A4476 -:104C70000024C361029B8460C16002610362C0E9D9 -:104C80000000C0E9051110BD08B5D0E90532934216 -:104C900001D1826882B98268013282605A1C426105 -:104CA00019700021D0E904329A4224BFC3684361DD -:104CB00000F0C0FE002008BD4FF0FF30FBE7000011 -:104CC00070B5302304460E4683F31188A568A5B15C -:104CD000A368A269013BA360531CA36115782269F4 -:104CE000934224BFE368A361E3690BB12046984770 -:104CF000002383F31188284607E03146204600F060 -:104D000089FE0028E2DA85F3118870BD2DE9F74F9E -:104D100004460E4617469846D0F81C904FF0300ACD -:104D20008AF311884FF0000B154665B12A463146CB -:104D30002046FFF741FF034660B94146204600F098 -:104D400069FE0028F1D0002383F31188781B03B09B -:104D5000BDE8F08FB9F1000F03D001902046C8479D -:104D6000019B8BF31188ED1A1E448AF31188DCE74E -:104D7000C160C361009B82600362C0E905111144F8 -:104D8000C0E9000001617047F8B504460D461646BB -:104D9000302383F31188A768A7B1A368013BA36000 -:104DA00063695A1C62611D70D4E904329A4224BFBF -:104DB000E3686361E3690BB120469847002080F304 -:104DC000118807E03146204600F024FE0028E2DA90 -:104DD00087F31188F8BD0000D0E9052310B59A4289 -:104DE00001D182687AB982680021013282605A1C3E -:104DF00082611C7803699A4224BFC368836100F012 -:104E000019FE204610BD4FF0FF30FBE72DE9F74FAC -:104E100004460E4617469846D0F81C904FF0300ACC -:104E20008AF311884FF0000B154665B12A463146CA -:104E30002046FFF7EFFE034660B94146204600F0EA -:104E4000E9FD0028F1D0002383F31188781B03B01B -:104E5000BDE8F08FB9F1000F03D001902046C8479C -:104E6000019B8BF31188ED1A1E448AF31188DCE74D -:104E7000026843681143016003B11847704700009E -:104E80001430FFF743BF00004FF0FF331430FFF73B -:104E90003DBF00003830FFF7B9BF00004FF0FF33CF -:104EA0003830FFF7B3BF00001430FFF709BF000030 -:104EB0004FF0FF311430FFF703BF00003830FFF729 -:104EC00063BF00004FF0FF323830FFF75DBF0000D6 -:104ED000012914BF6FF0130000207047FFF744BD95 -:104EE000044B036000234360C0E9023301230374D1 -:104EF000704700BF0882000810B53023044683F3D2 -:104F00001188FFF75BFD02230020237480F31188D2 -:104F100010BD000038B5C36904460D461BB9042115 -:104F20000844FFF7A5FF294604F11400FFF7ACFE83 -:104F3000002806DA201D4FF40061BDE83840FFF775 -:104F400097BF38BD026843681143016003B1184739 -:104F50007047000013B5406B00F58054D4F8A438B6 -:104F60001A681178042914D1017C022911D1197908 -:104F7000012312898B4013420BD101A94C3002F05E -:104F8000F3F9D4F8A4480246019B2179206800F087 -:104F9000DFF902B010BD0000143002F075B9000056 -:104FA0004FF0FF33143002F06FB900004C3002F0C4 -:104FB00047BA00004FF0FF334C3002F041BA000016 -:104FC000143002F043B900004FF0FF31143002F00A -:104FD0003DB900004C3002F013BA00004FF0FF3230 -:104FE0004C3002F00DBA00000020704710B500F5FB -:104FF0008054D4F8A4381A681178042917D1017C98 -:10500000022914D15979012352898B4013420ED1C0 -:10501000143002F0D5F8024648B1D4F8A4484FF451 -:10502000407361792068BDE8104000F07FB910BD81 -:10503000406BFFF7DBBF0000704700007FB5124BED -:1050400001250426044603600023057400F1840250 -:1050500043602946C0E902330C4B0290143001939F -:105060004FF44073009602F087F8094B04F694421F -:10507000294604F14C000294CDE900634FF44073DB -:1050800002F04EF904B070BD3082000831500008C3 -:10509000554F00080A68302383F311880B790B33CE -:1050A00042F823004B79133342F823008B7913B174 -:1050B0000B3342F8230000F58053C3F8A4180223F1 -:1050C0000374002080F311887047000038B5037F17 -:1050D000044613B190F85430ABB90125201D0221CC -:1050E000FFF730FF04F114006FF00101257700F0A5 -:1050F000ADFC04F14C0084F854506FF00101BDE8A0 -:10510000384000F0A3BC38BD10B50121044604307E -:10511000FFF718FF0023237784F8543010BD0000F8 -:1051200038B504460025143002F03EF804F14C0076 -:10513000257702F00DF9201D84F854500121FFF766 -:1051400001FF2046BDE83840FFF750BF90F880309F -:1051500003F06003202B06D190F881200023212A40 -:1051600003D81F2A06D800207047222AFBD1C0E9A5 -:105170001D3303E0034A426707228267C3670120A9 -:10518000704700BF3C23002037B500F58055D5F8A7 -:10519000A4381A68117804291AD1017C022917D180 -:1051A0001979012312898B40134211D100F14C046B -:1051B000204602F08DF958B101A9204602F0D4F83A -:1051C000D5F8A4480246019B2179206800F0C0F878 -:1051D00003B030BD01F10B03F0B550F8236085B08A -:1051E00004460D46FEB1302383F3118804EB850796 -:1051F000301D0821FFF7A6FEFB6806F14C005B6935 -:105200001B681BB1019002F0BDF8019803A902F0E0 -:10521000ABF8024648B1039B2946204600F098F8B7 -:10522000002383F3118805B0F0BDFB685A6912684A -:10523000002AF5D01B8A013B1340F1D104F1800212 -:10524000EAE70000133138B550F82140ECB13023C3 -:1052500083F3118804F58053D3F8A4281368527996 -:1052600003EB8203DB689B695D6845B1042160182C -:10527000FFF768FE294604F1140001F0ABFF204659 -:10528000FFF7B4FE002383F3118838BD7047000098 -:1052900001F07EBA01234022002110B5044600F837 -:1052A000303BFCF77BFB0023C4E9013310BD000059 -:1052B00010B53023044683F3118824224160002175 -:1052C0000C30FCF76BFB204601F084FA022300202F -:1052D000237080F3118810BD70B500EB8103054683 -:1052E00050690E461446DA6018B110220021FCF70E -:1052F00055FBA06918B110220021FCF74FFB314685 -:105300002846BDE8704001F065BB0000836820229C -:10531000002103F0011310B5044683601030FCF740 -:105320003DFB2046BDE8104001F0E0BBF0B4012594 -:1053300000EB810447898D40E4683D43A4694581C1 -:1053400023600023A2606360F0BC01F0FDBB00009D -:10535000F0B4012500EB810407898D40E4683D43EA -:105360006469058123600023A2606360F0BC01F0E2 -:1053700073BC000070B5022300250446242203708C -:105380002946C0F888500C3040F8045CFCF706FB56 -:10539000204684F8705001F0B1FA63681B6823B1AD -:1053A00029462046BDE87040184770BD0378052B9C -:1053B00010B504460AD080F88C300523037043688A -:1053C0001B680BB1042198470023A36010BD0000A7 -:1053D0000178052906D190F88C20436802701B687B -:1053E00003B118477047000070B590F8703004465C -:1053F00013B1002380F8703004F18002204601F0E0 -:1054000099FB63689B68B3B994F8803013F060052A -:1054100035D00021204601F08BFE0021204601F00E -:105420007BFE63681B6813B106212046984706235C -:1054300084F8703070BD204698470028E4D0B4F856 -:105440008630A26F9A4288BFA36794F98030A56F17 -:10545000002B4FF0300380F20381002D00F0F2802A -:10546000092284F8702083F3118800212046D4E9B2 -:105470001D23FFF76DFF002383F31188DAE794F80B -:10548000812003F07F0343EA022340F20232934279 -:1054900000F0C58021D8B3F5807F48D00DD8012B0E -:1054A0003FD0022B00F09380002BB2D104F1880290 -:1054B00062670222A267E367C1E7B3F5817F00F06C -:1054C0009B80B3F5407FA4D194F88230012BA0D10A -:1054D000B4F8883043F0020332E0B3F5006F4DD0EA -:1054E00017D8B3F5A06F31D0A3F5C063012B90D8C6 -:1054F0006368204694F882205E6894F88310B4F8BC -:105500008430B047002884D0436863670368A3678A -:105510001AE0B3F5106F36D040F6024293427FF4A2 -:1055200078AF5C4B63670223A3670023C3E794F85B -:105530008230012B7FF46DAFB4F8883023F0020382 -:10554000A4F88830C4E91D55E56778E7B4F88030E1 -:10555000B3F5A06F0ED194F88230204684F88A30DB -:1055600001F02AFA63681B6813B1012120469847AD -:10557000032323700023C4E91D339CE704F18B034C -:1055800063670123C3E72378042B10D1302383F30F -:1055900011882046FFF7BAFE85F31188032163685E -:1055A00084F88B5021701B680BB12046984794F803 -:1055B0008230002BDED084F88B30042323706368A4 -:1055C0001B68002BD6D0022120469847D2E794F8DA -:1055D000843020461D0603F00F010AD501F09CFA25 -:1055E000012804D002287FF414AF2B4B9AE72B4BF1 -:1055F00098E701F083FAF3E794F88230002B7FF408 -:1056000008AF94F8843013F00F01B3D01A06204687 -:1056100002D501F0A5FDADE701F096FDAAE794F8EB -:105620008230002B7FF4F5AE94F8843013F00F0134 -:10563000A0D01B06204602D501F07AFD9AE701F0C2 -:105640006BFD97E7142284F8702083F311882B46B2 -:105650002A4629462046FFF769FE85F31188E9E6C8 -:105660005DB1152284F8702083F311880021204653 -:10567000D4E91D23FFF75AFEFDE60B2284F87020C3 -:1056800083F311882B462A4629462046FFF760FE01 -:10569000E3E700BF60820008588200085C820008CF -:1056A00038B590F870300446002B3ED0063BDAB295 -:1056B0000F2A34D80F2B32D8DFE803F03731310806 -:1056C000223231313131313131313737856FB0F8F4 -:1056D00086309D4214D2C3681B8AB5FBF3F203FBEC -:1056E00012556DB9302383F311882B462A4629467B -:1056F000FFF72EFE85F311880A2384F870300EE040 -:10570000142384F87030302383F31188002320465B -:105710001A461946FFF70AFE002383F3118838BDA5 -:10572000C36F03B198470023E7E70021204601F04B -:10573000FFFC0021204601F0EFFC63681B6813B1F9 -:105740000621204698470623D7E7000010B590F8B9 -:1057500070300446142B29D017D8062B05D001D859 -:105760001BB110BD093B022BFBD80021204601F0E4 -:10577000DFFC0021204601F0CFFC63681B6813B1F9 -:10578000062120469847062319E0152BE9D10B2363 -:1057900080F87030302383F3118800231A461946AD -:1057A000FFF7D6FD002383F31188DAE7C3689B690E -:1057B0005B68002BD5D1C36F03B19847002384F8F1 -:1057C0007030CEE700238268037503691B6899680F -:1057D0009142FBD25A680360426010605860704783 -:1057E00000238268037503691B6899689142FBD89E -:1057F0005A680360426010605860704708B50846F8 -:10580000302383F311880A7D0023052A06D8DFE8B8 -:1058100002F00B050503120E826913604FF0FF338F -:105820008361FFF7CFFF002383F3118808BD8269EE -:10583000936801339360D0E9003213605A60EDE75A -:10584000FFF7C0BF054BD968087518680268536038 -:105850001A600122D8600275FAF7DCBD30540020CE -:105860000C4B30B5DD684B1C87B004460FD02B467F -:10587000094A684600F07EF92046FFF7E3FF009BE7 -:1058800013B1684600F080F9A86907B030BDFFF792 -:10589000D9FFF9E730540020FD57000838B50C4D0A -:1058A00004468161EB6881689A68914203D8BDE83B -:1058B0003840FFF787BF1846FFF792FF01230146E4 -:1058C000EC6020462375BDE83840FAF7A3BD00BF61 -:1058D00030540020044B1A68DB6890689B6898423B -:1058E00094BF00200120704730540020084B10B5B1 -:1058F0001C68D868226853601A600122DC60227537 -:10590000FFF76EFF01462046BDE81040FAF782BD62 -:105910003054002038B50123084C00252370656001 -:1059200001F012FE01F038FE0549064801F00CFFB7 -:105930000223237085F3118838BD00BF98560020DC -:10594000688200083054002008B572B6044B186510 -:1059500000F022FD00F0E4FD024B03221A70FEE786 -:10596000305400209856002000F044B9034A516892 -:1059700053685B1A9842FBD8704700BF001000E0E4 -:105980008B600223086108468B8270478368A3F10D -:10599000840243F8142C026943F8442C426943F80A -:1059A000402C094A43F8242CC268A3F1200043F894 -:1059B000182C022203F80C2C002203F80B2C034AAB -:1059C00043F8102C704700BF2D040008305400200D -:1059D00008B5FFF7DBFFBDE80840FFF731BF000067 -:1059E000024BDB6898610F20FFF72CBF305400207A -:1059F000302383F31188FFF7F3BF000008B5014699 -:105A0000302383F311880820FFF72AFF002383F354 -:105A1000118808BD064BDB6839B1426818605A60CE -:105A2000136043600420FFF71BBF4FF0FF30704747 -:105A3000305400200368984206D01A680260506013 -:105A400018469961FFF7FCBE7047000038B5044660 -:105A50000D462068844200D138BD036823605C6035 -:105A60008561FFF7EDFEF4E7036810B59C68A2427C -:105A70000CD85C688A600B604C6021605960996842 -:105A80008A1A9A604FF0FF33836010BD121B1B68A7 -:105A9000ECE700000A2938BF0A2170B504460D461C -:105AA0000A26601901F04AFD01F032FD041BA542EF -:105AB00003D8751C04462E46F3E70A2E04D90120AC -:105AC000BDE8704001F080BE70BD0000F8B5144B19 -:105AD0000D460A2A4FF00A07D96103F110018260CE -:105AE00038BF0A2241601969144601604860186194 -:105AF000A81801F013FD01F00BFD431B0646A3425D -:105B000006D37C1C28192746354601F017FDF2E71D -:105B10000A2F04D90120BDE8F84001F055BEF8BDB8 -:105B200030540020F8B506460D4601F0F1FC0F4A4E -:105B3000134653F8107F9F4206D12A46014630464D -:105B4000BDE8F840FFF7C2BFD169BB68441A2C1901 -:105B500028BF2C46A34202D92946FFF79BFF2246C5 -:105B600031460348BDE8F840FFF77EBF30540020BF -:105B700040540020C0E90323002310B45DF8044B17 -:105B80004361FFF7CFBF000010B5194C236998425D -:105B90000DD08168D0E9003213605A609A680A44D7 -:105BA0009A60002303604FF0FF33A36110BD0268C9 -:105BB000234643F8102F53600022026022699A4264 -:105BC00003D1BDE8104001F0B3BC936881680B4479 -:105BD000936001F09DFC2269E1699268441AA24237 -:105BE000E4D91144BDE81040091AFFF753BF00BFC4 -:105BF000305400202DE9F047DFF8BC8008F1100791 -:105C00002C4ED8F8105001F083FCD8F81C40AA683C -:105C1000031B9A423ED814444FF00009D5E90032E4 -:105C2000C8F81C4013605A60C5F80090D8F81030CE -:105C3000B34201D101F07CFC89F31188D5E903312D -:105C400028469847302383F311886B69002BD8D0FE -:105C500001F05EFC6A69A0EB040982464A450DD258 -:105C6000022001F0B1FD0022D8F81030B34208D173 -:105C700051462846BDE8F047FFF728BF121A2244D4 -:105C8000F2E712EB09092946384638BF4A46FFF7C2 -:105C9000EBFEB5E7D8F81030B34208D01444C8F88A -:105CA0001C00211AA960BDE8F047FFF7F3BEBDE86C -:105CB000F08700BF405400203054002038B501F078 -:105CC00027FC054AD2E90845031B181945F10001D4 -:105CD000C2E9080138BD00BF3054002000207047E1 -:105CE000FEE70000704700004FF0FF3070470000F3 -:105CF00002290CD0032904D00129074818BF00202D -:105D00007047032A05D8054800EBC20070470448D5 -:105D100070470020704700BF408300084C230020DC -:105D2000F482000870B59AB005460846144601A9E9 -:105D300000F0C2F801A8FBF729FE431C0022C6B2FE -:105D40005B001046C5E9003423700323023404F8D5 -:105D5000013C01ABD1B202348E4201D81AB070BD01 -:105D600013F8011B013204F8010C04F8021CF1E7DE -:105D700008B5302383F311880348FFF705FA0023A1 -:105D800083F3118808BD00BFA056002090F8803032 -:105D900003F01F02012A07D190F881200B2A03D1BA -:105DA0000023C0E91D3315E003F06003202B08D168 -:105DB000B0F884302BB990F88120212A03D81F2A0B -:105DC00004D8FFF7C3B9222AEBD0FAE7034A4267A7 -:105DD00007228267C3670120704700BF432300206A -:105DE00007B5052917D8DFE801F01916031919209E -:105DF000302383F31188104A01210190FFF76CFAD8 -:105E0000019802210D4AFFF767FA0D48FFF788F95C -:105E1000002383F3118803B05DF804FB302383F380 -:105E200011880748FFF752F9F2E7302383F311880E -:105E30000348FFF769F9EBE794820008B88200088D -:105E4000A056002038B50C4D0C4C2A460C4904F1E4 -:105E50000800FFF767FF05F1CA0204F110000949C5 -:105E6000FFF760FF05F5CA7204F118000649BDE8A6 -:105E70003840FFF757BF00BF786F00204C23002049 -:105E8000748200087E8200088982000870B504468A -:105E900008460D46FBF77AFDC6B22046013403786A -:105EA0000BB9184670BD32462946FBF75BFD00284A -:105EB000F3D10120F6E700002DE9F84F05460C4626 -:105EC000FBF764FD2A49C6B22846FFF7DFFF08B199 -:105ED0000136F6B227492846FFF7D8FF08B1103639 -:105EE000F6B2632E0DD8DFF88890DFF888A0224F35 -:105EF000DFF88CB0DFF88C802E7846B92670BDE8CC -:105F0000F88F29462046BDE8F84F02F063B8252EE9 -:105F10002AD1072249462846FBF724FD50B9D8F874 -:105F200000300735083444F8083CD8F8043044F809 -:105F3000043CE1E7082251462846FBF713FD98B9D7 -:105F4000A21C0E4B197802320909C95D02F8041C23 -:105F500013F8011B01F00F015B45C95D02F8031C3A -:105F6000F0D118340835C7E7013504F8016BC3E7F1 -:105F700060830008898200086883000800E8F11F38 -:105F80000CE8F11FF27F0008BFF34F8F044B1A6932 -:105F90005107FCD1D3F810215207F8D1704700BF48 -:105FA0000020005208B50D4B1B78ABB9FFF7ECFF92 -:105FB0000B4BDA68D10704D50A4A5A6002F18832DD -:105FC0005A60D3F80C21D20706D5064AC3F804213B -:105FD00002F18832C3F8042108BD00BFD671002049 -:105FE000002000522301674508B5114B1B78F3B917 -:105FF000104B1A69510703D5DA6842F04002DA60A3 -:10600000D3F81021520705D5D3F80C2142F04002F5 -:10601000C3F80C21FFF7B8FF064BDA6842F0010223 -:10602000DA60D3F80C2142F00102C3F80C2108BD5C -:10603000D6710020002000520F289ABF00F5806022 -:1060400040040020704700004FF40030704700000B -:10605000102070470F2808B50BD8FFF7EDFF00F5AB -:1060600000330268013204D104308342F9D10120A7 -:1060700008BD0020FCE700000F2838B505463FD8D2 -:10608000FFF782FF1F4CFFF78DFF4FF0FF3307280C -:106090006361C4F814311DD82361FFF775FF030253 -:1060A00043F02403E360E36843F08003E360236983 -:1060B0005A07FCD42846FFF767FFFFF7BDFF4FF4F0 -:1060C000003100F009FA2846FFF78EFFBDE838409E -:1060D000FFF7C0BFC4F81031FFF756FFA0F1080367 -:1060E0001B0243F02403C4F80C31D4F80C3143F004 -:1060F0008003C4F80C31D4F810315B07FBD4D9E726 -:10610000002038BD002000522DE9F84F05460C460E -:10611000104645EA0203DE0602D00020BDE8F88FF3 -:1061200020F01F00DFF8BCB0DFF8BCA0FFF73AFF9B -:1061300004EB0008444503D10120FFF755FFEDE7CC -:1061400020222946204601F013FF10B920352034C3 -:10615000F0E72B4605F120021F68791CDDD10433DE -:106160009A42F9D105F178431B481C4EB3F5801FC4 -:106170001B4B38BF184603F1F80332BFD946D1464E -:106180001E46FFF701FF0760A5EB040C336804F11E -:106190001C0143F002033360231FD9F8007017F08D -:1061A0000507FAD153F8042F8B424CF80320F4D1A1 -:1061B000BFF34F8FFFF7E8FE4FF0FF332022214659 -:1061C00003602846336823F00203336001F0D0FEF9 -:1061D0000028BBD03846B0E7142100520C200052F2 -:1061E00014200052102000521021005210B5084C0B -:1061F000237828B11BB9FFF7D5FE0123237010BD0A -:10620000002BFCD02070BDE81040FFF7EDBE00BFB2 -:10621000D67100202DE9F04F0D4685B0814658B16A -:1062200011F00D0614BF2022082211F0080301937B -:1062300004D0431E03426AD0002435E0002E37D03C -:1062400009F11F0121F01F094FF00108324F05F03D -:106250000403DFF8D0A005EA080BBBF1000F32D031 -:106260007869C0072FD408F101080C37B8F1060F80 -:10627000F3D19EB9294D4946A819019201F0AEF912 -:10628000044600283AD11836019A782EF3D14946AF -:1062900001F0A4F90446002830D1019A494620486B -:1062A00001F09CF9044668BB204605B0BDE8F08FBC -:1062B0000029C9D101462846029201F08FF904460F -:1062C000E0B9029AC0E713B178694107CBD5AC07B2 -:1062D00002D578698007C6D5019911B1786901079F -:1062E000C1D51820494600FB08A0CDE9022301F0E2 -:1062F00075F90446DDE902230028B4D04A4600219E -:10630000204601E04A460021FBF748FBCCE7024665 -:10631000002E95D198E700BF7C830008087200200A -:10632000D8710020F07100200121FFF773BF000039 -:10633000F8B5144D01241827134E40F2FF32002106 -:106340000120FBF72BFB07FB046001342A6955F899 -:106350000C1F01F02FF9062CF5D137254FF4C0544E -:106360002046FFF7E1FF014628B122460748BDE875 -:10637000F84001F01FB9C4EBC404013D4FEAD40456 -:10638000EED1F8BD7C830008F0710020D8710020A8 -:1063900008B101F095B9704738B5054D00240334B4 -:1063A000696855F80C0B00F0A9F8122CF7D138BD2C -:1063B0007C83000838B5EFF311859DB9EFF30584B0 -:1063C000C4F30804302334B183F31188FFF776FC5B -:1063D00085F3118838BD83F31188FFF76FFC84F3D0 -:1063E000118838BDBDE83840FFF768BC10B5FFF72D -:1063F000E1FF104CC008104A002340EA4170C90870 -:10640000A0FB04ECA0FB020E1CEB0000A1FB044C63 -:10641000A1FB02125B41001943EB0C0011EB0E01D2 -:1064200042F10002411842F10000090941EA0070FE -:1064300010BD00BFCFF753E3A59BC4200244074B18 -:10644000D2B210B5904200D110BD441C00B253F836 -:10645000200041F8040BE0B2F4E700BF50400058C0 -:106460000E4B30B51C6F240405D41C6F1C671C6FC9 -:1064700044F400441C670A4C02442368D2B243F43B -:1064800080732360074B904200D130BD441C51F80B -:10649000045B00B243F82050E0B2F4E70044025835 -:1064A000004802585040005807B5012201A90020B9 -:1064B000FFF7C4FF019803B05DF804FB13B5044671 -:1064C000FFF7F2FFA04205D0012201A900200194AC -:1064D000FFF7C6FF02B010BD0144BFF34F8F064B5C -:1064E000884204D3BFF34F8FBFF36F8F7047C3F859 -:1064F0005C022030F4E700BF00ED00E00144BFF390 -:106500004F8F064B884204D3BFF34F8FBFF36F8F7B -:106510007047C3F870022030F4E700BF00ED00E0E0 -:1065200070470000114BDA6952021ED59A69D007F4 -:1065300004D50F4A9A6002F144329A600B4BDA6933 -:10654000D107FCD41A6A22F480021A629A6942F0D6 -:1065500002029A61DA69D207FCD49A6942F0010218 -:106560009A61024AD369DB07FCD4704700200052CD -:106570003B2A1908074B45F255521A6003225A600C -:1065800040F2FF729A604CF6CC421A600122024B34 -:106590001A7070470048005884720020034B1B7823 -:1065A0001BB1034B4AF6AA221A607047847200207E -:1065B00000480058034B1A681AB9034AD2F8D0248D -:1065C0001A6070478072002000400258024B4FF45E -:1065D0008032C3F8D02470470040025808B5FFF756 -:1065E000E9FF024B1868C0F3806008BD807200208C -:1065F00070B5BFF34F8FBFF36F8F1A4A0021C2F8F7 -:106600005012BFF34F8FBFF36F8F536943F40033C2 -:106610005361BFF34F8FBFF36F8FC2F88410BFF386 -:106620004F8FD2F8803043F6E074C3F3C900C3F350 -:106630004E335B0103EA0406014646EA81750139DF -:10664000C2F86052F9D2203B13F1200FF2D1BFF310 -:106650004F8F536943F480335361BFF34F8FBFF3C0 -:106660006F8F70BD00ED00E0FEE70000214B224877 -:10667000224A70B5904237D3214BC11EDA1C121A40 -:1066800022F003028B4238BF00220021FBF786F97B -:106690001C4A0023C2F88430BFF34F8FD2F88030F9 -:1066A00043F6E074C3F3C900C3F34E335B0103EA5E -:1066B0000406014646EA81750139C2F86C52F9D2E6 -:1066C000203B13F1200FF2D1BFF34F8FBFF36F8F39 -:1066D000BFF34F8FBFF36F8F0023C2F85032BFF369 -:1066E0004F8FBFF36F8F70BD53F8041B40F8041B2E -:1066F000C0E700BFAC8500087874002078740020E3 -:106700007874002000ED00E0054B996B21EA000150 -:1067100099631A6E22EA00021A661B6E704700BF68 -:106720000045025870B5D0E9244300224FF0FF35F0 -:106730009E6804EB42135101D3F80009002805DAE2 -:10674000D3F8000940F08040C3F80009D3F8000BEB -:10675000002805DAD3F8000B40F08040C3F8000BA6 -:10676000013263189642C3F80859C3F8085BE0D2B7 -:106770004FF00113C4F81C3870BD0000890141F0CE -:106780002001016103699B06FCD41220FFF7EEB8DB -:1067900010B50A4C2046FEF77DFD094BC4F8903039 -:1067A000084BC4F89430084C2046FEF773FD074BA5 -:1067B000C4F89030064BC4F8943010BD88720020A5 -:1067C00000000840E8830008247300200000044013 -:1067D000F483000870B503780546012B58D13F4B70 -:1067E000D0F89040984254D13D4B0E2165209A6BD1 -:1067F00042F000629A631A6E42F000621A661B6EE3 -:10680000384BD3F8802042F00062C3F88020D3F8E0 -:10681000802022F00062C3F88020D3F88030FEF799 -:106820009FF9314BE360314BC4F800380023D5F8B1 -:106830009060C4F8003EC02323604FF40413A363A8 -:106840003369002BFCDA01230C203361FFF78EF84B -:106850003369DB07FCD41220FFF788F83369002B7B -:10686000FCDA00262846A660FFF75CFF6B68C4F8D8 -:106870001068DB68C4F81468C4F81C6863BB1C4B60 -:10688000A3614FF0FF336361A36843F00103A3608A -:1068900070BD184B9842C9D1114B4FF080609A6B74 -:1068A00042F000729A631A6E42F000721A661B6E12 -:1068B0000C4BD3F8802042F00072C3F88020D3F84C -:1068C000802022F00072C3F88020D3F88030FFF7D8 -:1068D0001BFF0E214D20A2E7074BD1E78872002055 -:1068E00000450258004402584014004003002002B2 -:1068F000003C30C024730020083C30C0F8B5D0F80C -:106900009040054600214FF000662046FFF736FF15 -:10691000D5F8941000234FF001128F684FF0FF302C -:10692000C4F83438C4F81C2804EB431201339F42E6 -:10693000C2F80069C2F8006BC2F80809C2F8080B77 -:10694000F2D20B68D5F89020C5F898306362102316 -:106950001361166916F01006FBD11220FFF706F836 -:10696000D4F8003823F4FE63C4F80038A36943F474 -:10697000402343F01003A3610923C4F81038C4F87E -:1069800014380B4BEB604FF0C043C4F8103B094B7D -:10699000C4F8003BC4F81069C4F80039D5F8983041 -:1069A00003F1100243F48013C5F89820A362F8BDE8 -:1069B000C483000840800010D0F8902090F88A101E -:1069C000D2F8003823F4FE6343EA0113C2F800381A -:1069D000704700002DE9F84300EB8103D0F8905098 -:1069E0000C468046DA680FFA81F94801166806F00D -:1069F0000306731E022B05EB41134FF0000194BFF9 -:106A0000B604384EC3F8101B4FF0010104F1100317 -:106A100098BF06F1805601FA03F3916998BF06F515 -:106A2000004600293AD0578A04F1580137434901FA -:106A30006F50D5F81C180B430021C5F81C382B18D3 -:106A40000127C3F81019A7405369611E9BB3138A2D -:106A5000928B9B08012A88BF5343D8F89820981836 -:106A600042EA034301F140022146C8F89800284653 -:106A700005EB82025360FFF781FE08EB8900C368D3 -:106A80001B8A43EA845348341E4364012E51D5F8CF -:106A90001C381F43C5F81C78BDE8F88305EB49177F -:106AA000D7F8001B21F40041C7F8001BD5F81C18CB -:106AB00021EA0303C0E704F13F030B4A28462146BD -:106AC00005EB83035A60FFF759FE05EB4910D0F838 -:106AD000003923F40043C0F80039D5F81C3823EA04 -:106AE0000707D7E70080001000040002D0F89420C8 -:106AF0001268C0F89820FFF715BE00005831D0F892 -:106B0000903049015B5813F4004004D013F4001F87 -:106B10000CBF0220012070474831D0F89030490165 -:106B20005B5813F4004004D013F4001F0CBF022084 -:106B30000120704700EB8101CB68196A0B68136074 -:106B40004B6853607047000000EB810330B5DD688F -:106B5000AA691368D36019B9402B84BF402313601E -:106B60006B8A1468D0F890201C4402EB4110013C61 -:106B700009B2B4FBF3F46343033323F0030343EAA2 -:106B8000C44343F0C043C0F8103B2B6803F0030339 -:106B9000012B0ED1D2F8083802EB411013F4807F9C -:106BA000D0F8003B14BF43F0805343F00053C0F8CB -:106BB000003B02EB4112D2F8003B43F00443C2F821 -:106BC000003B30BD2DE9F041D0F8906005460C4601 -:106BD00006EB4113D3F8087B3A07C3F8087B08D5C6 -:106BE000D6F814381B0704D500EB8103DB685B681B -:106BF0009847FA071FD5D6F81438DB071BD505EBE5 -:106C00008403D968CCB98B69488A5A68B2FBF0F61C -:106C100000FB16228AB91868DA6890420DD2121A5F -:106C2000C3E90024302383F3118821462846FFF767 -:106C30008BFF84F31188BDE8F081012303FA04F28D -:106C40006B8923EA02036B81CB68002BF3D02146CA -:106C50002846BDE8F041184700EB81034A0170B5B2 -:106C6000DD68D0F890306C692668E66056BB1A443F -:106C70004FF40020C2F810092A6802F00302012A2A -:106C80000AB20ED1D3F8080803EB421410F4807F47 -:106C9000D4F8000914BF40F0805040F00050C4F810 -:106CA000000903EB4212D2F8000940F00440C2F898 -:106CB00000090122D3F8340802FA01F10143C3F8B4 -:106CC000341870BD19B9402E84BF40202060206860 -:106CD0001A442E8A8419013CB4FBF6F440EAC440FD -:106CE00040F00050C6E700002DE9F843D0F890606E -:106CF00005460C464F0106EB4113D3F8088918F0FE -:106D0000010FC3F808891CD0D6F81038DB0718D556 -:106D100000EB8103D3F80CC0DCF81430D3F800E0AA -:106D2000DA68964530D2A2EB0E024FF000091A60E5 -:106D3000C3F80490302383F31188FFF78DFF89F3A4 -:106D4000118818F0800F1DD0D6F834380126A640DF -:106D5000334217D005EB84030134D5F89050D3F8B3 -:106D60000CC0E4B22F44DCF8142005EB0434D2F854 -:106D700000E05168714514D3D5F8343823EA06068B -:106D8000C5F83468BDE8F883012303FA01F20389EA -:106D900023EA02030381DCF80830002BD1D09847A6 -:106DA000CFE7AEEB0103BCF81000834228BF0346D7 -:106DB000D7F8180980B2B3EB800FE3D89068A0F140 -:106DC000040959F8048FC4F80080A0EB090898441E -:106DD000B8F1040FF5D818440B4490605360C8E72D -:106DE0002DE9F84FD0F8905004466E69AB691E400B -:106DF00016F480586E6103D0BDE8F84FFEF7BABABA -:106E0000002E12DAD5F8003E9B0705D0D5F8003EDB -:106E100023F00303C5F8003ED5F80438204623F0DC -:106E20000103C5F80438FEF7D3FA370505D5204627 -:106E3000FFF778FC2046FEF7B9FAB0040CD5D5F878 -:106E4000083813F0060FEB6823F470530CBF43F4BB -:106E5000105343F4A053EB6031071BD56368DB6824 -:106E60001BB9AB6923F00803AB612378052B0CD168 -:106E7000D5F8003E9A0705D0D5F8003E23F003036D -:106E8000C5F8003E2046FEF7A3FA6368DB680BB145 -:106E900020469847F30200F1BA80B70226D5D4F80D -:106EA000909000274FF0010A09EB4712D2F8003BFF -:106EB00003F44023B3F5802F11D1D2F8003B002B0F -:106EC0000DDA62890AFA07F322EA0303638104EB0D -:106ED0008703DB68DB6813B13946204698470137E2 -:106EE000D4F89430FFB29B689F42DDD9F00619D5E3 -:106EF000D4F89000026AC2F30A1702F00F0302F4FA -:106F0000F012B2F5802F00F0CA80B2F5402F09D1FF -:106F100004EB8303002200F58050DB681B6A974274 -:106F200040F0B0803003D5F8185835D5E90303D5C3 -:106F300000212046FFF746FEAA0303D50121204683 -:106F4000FFF740FE6B0303D502212046FFF73AFE10 -:106F50002F0303D503212046FFF734FEE80203D5B3 -:106F600004212046FFF72EFEA90203D50521204665 -:106F7000FFF728FE6A0203D506212046FFF722FE0E -:106F80002B0203D507212046FFF71CFEEF0103D596 -:106F900008212046FFF716FE700340F1A780E9079D -:106FA00003D500212046FFF79FFEAA0703D5012144 -:106FB0002046FFF799FE6B0703D502212046FFF715 -:106FC00093FE2F0703D503212046FFF78DFEEE0623 -:106FD00003D504212046FFF787FEA80603D5052127 -:106FE0002046FFF781FE690603D506212046FFF7FC -:106FF0007BFE2A0603D507212046FFF775FEEB0529 -:1070000074D520460821BDE8F84FFFF76DBED4F8CF -:1070100090904FF0000B4FF0010AD4F894305FFAD3 -:107020008BF79B689F423FF638AF09EB4713D3F8C5 -:10703000002902F44022B2F5802F20D1D3F8002994 -:10704000002A1CDAD3F8002942F09042C3F8002944 -:10705000D3F80029002AFBDB3946D4F89000FFF76B -:107060008DFB22890AFA07F322EA0303238104EB4A -:107070008703DB689B6813B13946204698470BF1BC -:10708000010BCAE7910701D1D0F80080072A02F16D -:1070900001029CBF03F8018B4FEA18283FE704EB7D -:1070A000830300F58050DA68D2F818C0DCF80820B5 -:1070B000DCE9001CA1EB0C0C00218F4208D1DB683D -:1070C0009B699A683A449A605A683A445A6029E738 -:1070D00011F0030F01D1D0F800808C4501F10101BE -:1070E00084BF02F8018B4FEA1828E6E7BDE8F88F65 -:1070F00008B50348FFF774FEBDE80840FDF7DAB9AC -:107100008872002008B50348FFF76AFEBDE8084012 -:10711000FDF7D0B924730020D0F8903003EB411173 -:10712000D1F8003B43F40013C1F8003B7047000066 -:10713000D0F8903003EB4111D1F8003943F400133B -:10714000C1F8003970470000D0F8903003EB4111CE -:10715000D1F8003B23F40013C1F8003B7047000056 -:10716000D0F8903003EB4111D1F8003923F400132B -:10717000C1F800397047000030B50433039C017238 -:10718000002104FB0325C160C0E90653049B03638F -:10719000059BC0E90000C0E90422C0E90842C0E93B -:1071A0000A11436330BD00000022416AC260C0E999 -:1071B0000411C0E90A226FF00101FEF747BC00008C -:1071C000D0E90432934201D1C2680AB9181D704750 -:1071D00000207047036919600021C2680132C26053 -:1071E000C269134482699342036124BF436A036105 -:1071F000FEF720BC38B504460D46E3683BB1626932 -:107200000020131D1268A3621344E36207E0237A8F -:1072100033B929462046FEF7FDFB0028EDDA38BDDC -:107220006FF00100FBE70000C368C269013BC36067 -:107230004369134482699342436124BF436A4361B3 -:1072400000238362036B03B11847704770B5302386 -:10725000044683F31188866A3EB9FFF7CBFF0546E3 -:1072600018B186F31188284670BDA36AE26A13F844 -:10727000015B9342A36202D32046FFF7D5FF0023B0 -:1072800083F31188EFE700002DE9F84F04460E461E -:10729000174698464FF0300989F311880025AA4611 -:1072A000D4F828B0BBF1000F09D141462046FFF7C2 -:1072B000A1FF20B18BF311882846BDE8F88FD4E9EF -:1072C0000A12A7EB050B521A934528BF9346BBF150 -:1072D000400F1BD9334601F1400251F8040B914293 -:1072E00043F8040BF9D1A36A403640354033A3621A -:1072F000D4E90A239A4202D32046FFF795FF8AF386 -:107300001188BD42D8D289F31188C9E730465A4660 -:10731000FAF71EFBA36A5E445D445B44A362E7E7A1 -:1073200010B5029C0433017203FB0421C460C0E960 -:1073300006130023C0E90A33039B0363049BC0E9DF -:107340000000C0E90422C0E90842436310BD000008 -:10735000026A6FF00101C260426AC0E904220022A1 -:10736000C0E90A22FEF772BBD0E904239A4201D198 -:10737000C26822B9184650F8043B0B6070470023DE -:107380001846FAE7C3680021C2690133C360436944 -:10739000134482699342436124BF436A4361FEF709 -:1073A00049BB000038B504460D46E3683BB123698C -:1073B00000201A1DA262E2691344E36207E0237A07 -:1073C00033B929462046FEF725FB0028EDDA38BD03 -:1073D0006FF00100FBE7000003691960C268013A21 -:1073E000C260C269134482699342036124BF436A45 -:1073F000036100238362036B03B1184770470000E9 -:1074000070B530230D460446114683F31188866A11 -:107410002EB9FFF7C7FF10B186F3118870BDA36ABC -:107420001D70A36AE26A01339342A36204D3E16947 -:1074300020460439FFF7D0FF002080F31188EDE7E4 -:107440002DE9F84F04460D46904699464FF0300A14 -:107450008AF311880026B346A76A4FB949462046E9 -:10746000FFF7A0FF20B187F311883046BDE8F88F01 -:10747000D4E90A073A1AA8EB0607974228BF17462D -:10748000402F1BD905F1400355F8042B9D4240F8CD -:10749000042BF9D1A36A40364033A362D4E90A230E -:1074A0009A4204D3E16920460439FFF795FF8BF334 -:1074B00011884645D9D28AF31188CDE729463A4644 -:1074C000FAF746FAA36A3D443E443B44A362E5E72B -:1074D000D0E904239A4217D1C3689BB1836A8BB168 -:1074E000043B9B1A0ED01360C368013BC360C369A1 -:1074F0001A4483699A42026124BF436A03610023EC -:1075000083620123184670470023FBE700F05CBA52 -:10751000014B586A704700BF000C0040034B00222B -:1075200058631A610222DA60704700BF000C004005 -:10753000014B0022DA607047000C0040014B586399 -:10754000704700BF000C0040024B034A1A60034A18 -:107550005A607047D8730020787400200000022021 -:10756000074B494210B55C68201A08401968821A16 -:107570008A4203D3A24201D85A6010BD0020FCE722 -:10758000D873002008B5302383F31188FFF7E8FF94 -:10759000002383F3118808BD04480121044B0360D4 -:1075A0000023C0E901330C3000F016B9E07300206D -:1075B00085750008CB1D083A23F00703591A521AA3 -:1075C000012110B4D2080024C0E9004384600C30CB -:1075D0001C605A605DF8044B00F0FEB82DE9F84FCE -:1075E000364ECD1D0F46002818BF0646082A4FEA22 -:1075F000D50538BF082206F10C08341D91464046D7 -:1076000000F006F909F10701C9F1000E22462468CD -:107610006CB9404600F006F93368CBB308224946FE -:10762000E8009847044698B340E9026730E004EB6D -:10763000010CD4F804A00CEA0E0C0AF10100ACF124 -:10764000080304EBC0009842E0D9A0EB0C0CB5EBAA -:10765000EC0F4FEAEC0BD9D89C421CD204F1080283 -:10766000AB45A3EB02024FEAE202626009D9691C52 -:10767000ED43206803EBC1025D44556043F83100DF -:1076800022601C465F60404644F8086B00F0CAF870 -:107690002046BDE8F88FAA45216802D11160234633 -:1076A000EFE7013504EBC50344F8351003F1080199 -:1076B000401AC01058601360F1E700BFE07300206B -:1076C000F8B550F8043C044650F8085CA0F10806F0 -:1076D00007332F1D0C35DB0840F8043C284600F02A -:1076E00097F83B469F421A6801D0B34228D20AB1AC -:1076F000964225D244F8082C54F8042C1E6001321E -:1077000054F8081C06EBC200814206D148680244C6 -:1077100044F8042C0A6844F8082C5868411C03EB10 -:10772000C1018E4207D154F8042C013202445A6040 -:1077300054F8082C1A602846BDE8F84000F072B8EA -:107740001346CFE7FEE7000070B51B4B002504464B -:1077500086B058600E4685620163FCF783FE04F133 -:107760001003A560E562C4E904334FF0FF33C4E9B8 -:107770000044C4E90635FFF7CBFE2B46024604F170 -:1077800034012046C4E9082380230C4A2565FEF70E -:10779000F7F801230A4AE0600092037568467268B0 -:1077A0000192B268CDE90223064BCDE90435FEF71C -:1077B0000FF906B070BD00BF985600200084000885 -:1077C0000584000845770008024AD36A1843D0624E -:1077D000704700BF30540020C0E90000816070474E -:1077E0008368013B002B10B583600CDA074BDC6823 -:1077F0004368A061206063601C6044600520FEF760 -:1078000021F8A06910BD0020FCE700BF3054002023 -:1078100008B5302383F31188FFF7E2FF002383F3D9 -:10782000118808BD08B5302383F3118883680133BC -:10783000002B836007DC036800211A680260506037 -:107840001846FEF72BF8002383F3118808BD0000CB -:107850004B6843608B688360CB68C3600B6943618E -:107860004B6903628B6943620B68036070470000D9 -:1078700008B53C4B40F2FF713B48D3F888200A43DF -:10788000C3F88820D3F8882022F4FF6222F0070290 -:10789000C3F88820D3F88830344B1A6C0A431A6432 -:1078A0009A6E0A439A66324A9B6E1146FFF7D0FFE2 -:1078B00000F5806002F11C01FFF7CAFF00F580604F -:1078C00002F13801FFF7C4FF00F5806002F15401B6 -:1078D000FFF7BEFF00F5806002F17001FFF7B8FF0F -:1078E00000F5806002F18C01FFF7B2FF00F58060C7 -:1078F00002F1A801FFF7ACFF00F5806002F1C401BE -:10790000FFF7A6FF00F5806002F1E001FFF7A0FF9E -:1079100000F5806002F1FC01FFF79AFF02F58C711F -:1079200000F58060FFF794FF00F010F9114BD3F8D9 -:10793000902242F00102C3F89022D3F8942242F040 -:107940000102C3F894220522C3F898204FF0605238 -:10795000C3F89C20084AC3F8A020BDE80840FEF701 -:10796000E1BD00BF00440258000002580045025823 -:107970000C84000800ED00E01F00080308B500F0CB -:10798000C3FAFDF7C7FF0D4BDA6B42F04002DA6332 -:107990005A6E22F040025A665B6E094B1A6842F03A -:1079A00008021A601A6842F004021A60FEF702FE2A -:1079B000FEF7BEFCBDE80840FEF744BA0045025899 -:1079C00000180248704700000E4B9A6C42F0080203 -:1079D0009A641A6F42F008021A670B4A1B6FD36B46 -:1079E00043F00803D363C722084B9A624FF0FF327B -:1079F000DA6200229A615A63DA605A6001225A619F -:107A00001A607047004502580010005C000C0040EE -:107A1000094A08B51169D3680B40D9B29B076FEAD0 -:107A20000101116107D5302383F31188FDF79CFF15 -:107A3000002383F3118808BD000C0040044BDA6B6F -:107A40000243DA635A6E104358665B6E704700BF9C -:107A50000045025808B53C4B4FF0FF31D3F8802069 -:107A600062F00042C3F88020D3F8802002F0004288 -:107A7000C3F88020D3F88020D3F88420C3F8841082 -:107A8000D3F884200022C3F88420D3F88400D86F70 -:107A900040F0FF4040F4FF0040F4DF4040F07F0042 -:107AA000D867D86F20F0FF4020F4FF0020F4DF40BB -:107AB00020F07F00D867D86FD3F888006FEA405075 -:107AC0006FEA5050C3F88800D3F88800C0F30A006A -:107AD000C3F88800D3F88800D3F89000C3F890105A -:107AE000D3F89000C3F89020D3F89000D3F8940016 -:107AF000C3F89410D3F89400C3F89420D3F89400FA -:107B0000D3F89800C3F89810D3F89800C3F89820D9 -:107B1000D3F89800D3F88C00C3F88C10D3F88C00FD -:107B2000C3F88C20D3F88C00D3F89C00C3F89C10C9 -:107B3000D3F89C10C3F89C20D3F89C30FCF73CFE93 -:107B4000BDE8084000F0B4B90044025808B501226D -:107B5000504BC3F80821504B5A6D42F002025A654F -:107B6000DA6F42F00202DA670422DB6F4B4BDA6015 -:107B70005A689104FCD54A4A1A6001229A60494A1F -:107B8000DA6000221A614FF440429A61434B9A69CD -:107B90009204FCD51A6842F480721A60424B1A6F44 -:107BA00012F4407F04D04FF480321A6700221A6723 -:107BB0001A6842F001021A603B4B1A685007FCD564 -:107BC00000221A611A6912F03802FBD101211960F2 -:107BD0004FF0804159605A67344ADA62344A1A6178 -:107BE0001A6842F480321A602F4B1A689103FCD550 -:107BF0001A6842F480521A601A689204FCD52D4A21 -:107C00002D499A6200225A63196301F57C01DA63F7 -:107C100001F5E77199635A64284A1A64284ADA62BE -:107C20001A6842F0A8521A601F4B1A6802F02852D4 -:107C3000B2F1285FF9D148229A614FF48862DA6183 -:107C400040221A621F4ADA641F4A1A651F4A5A659F -:107C50001F4A9A6532231F4A1360136803F00F030B -:107C6000022BFAD1104A136943F00303136113691D -:107C700003F03803182BFAD14FF00050FFF7DEFE67 -:107C80004FF08040FFF7DAFE4FF00040BDE80840BB -:107C9000FFF7D4BE0080005100450258004802584A -:107CA00000C000F004000001004402580000FF0181 -:107CB000008890083220600063020901470E050821 -:107CC000DD0BBF0120000020000001100910E000C2 -:107CD00000010110002000524FF0B04208B5D2F868 -:107CE000883003F00103C2F8883023B1044A1368D6 -:107CF0000BB150689847BDE80840FCF7DBBB00BFFC -:107D0000F87300204FF0B04208B5D2F8883003F085 -:107D10000203C2F8883023B1044A93680BB1D068DB -:107D20009847BDE80840FCF7C5BB00BFF8730020CA -:107D30004FF0B04208B5D2F8883003F00403C2F81F -:107D4000883023B1044A13690BB150699847BDE8E4 -:107D50000840FCF7AFBB00BFF87300204FF0B04203 -:107D600008B5D2F8883003F00803C2F8883023B190 -:107D7000044A93690BB1D0699847BDE80840FCF705 -:107D800099BB00BFF87300204FF0B04208B5D2F89D -:107D9000883003F01003C2F8883023B1044A136A14 -:107DA0000BB1506A9847BDE80840FCF783BB00BFA1 -:107DB000F87300204FF0B04310B5D3F8884004F4B6 -:107DC0007872C3F88820A30604D5124A936A0BB1CF -:107DD000D06A9847600604D50E4A136B0BB1506BFE -:107DE0009847210604D50B4A936B0BB1D06B98478B -:107DF000E20504D5074A136C0BB1506C9847A305F4 -:107E000004D5044A936C0BB1D06C9847BDE8104080 -:107E1000FCF750BBF87300204FF0B04310B5D3F817 -:107E2000884004F47C42C3F88820620504D5164AD1 -:107E3000136D0BB1506D9847230504D5124A936D0D -:107E40000BB1D06D9847E00404D50F4A136E0BB107 -:107E5000506E9847A10404D50B4A936E0BB1D06EB7 -:107E60009847620404D5084A136F0BB1506F9847C6 -:107E7000230404D5044A936F0BB1D06F9847BDE833 -:107E80001040FCF717BB00BFF873002008B503488B -:107E9000FCF7E0FDBDE80840FCF70CBBC44F002038 -:107EA00008B5FFF7B5FDBDE80840FCF703BB0000CF -:107EB000062108B50846FCF753FE06210720FCF70B -:107EC0004FFE06210820FCF74BFE06210920FCF797 -:107ED00047FE06210A20FCF743FE06211720FCF787 -:107EE0003FFE06212820FCF73BFE09217A20FCF703 -:107EF00037FE07213220FCF733FE0C215220BDE86B -:107F00000840FCF72DBE000008B5FFF7A3FD00F008 -:107F10000DF8FCF7E3FFFDF7BBF9FDF78DF8FFF770 -:107F200051FDBDE80840FFF7F1BA00000023054A03 -:107F300019460133102BC2E9001102F10802F8D1F1 -:107F4000704700BFF87300200B460146184600F04A -:107F500001B8000010B5054C13462CB10A46014685 -:107F60000220AFF3008010BD2046FCE700000000B7 -:107F700010B501390244904201D1002005E0037898 -:107F800011F8014FA34201D0181B10BD0130F2E7D8 -:107F90002DE9F041A3B1C91A17780144044603F151 -:107FA000FF3C8C42204601D9002009E00578BD4203 -:107FB00004F10104F5D10CEB0405D618A54201D15A -:107FC000BDE8F08115F8018D16F801EDF045F5D00A -:107FD000E7E70000034611F8012B03F8012B002A04 -:107FE000F9D170476F72672E6172647570696C6F3A -:107FF000742E437562654E6F6465000053544D33B3 -:108000003248373F3F3F0053544D3332483733787F -:108010002F3732780053544D3332483734332F37AB -:1080200035332F373530000001105A000310590046 -:10803000012058000320560040A2E4F16468910634 -:108040000041A3E5F26569920700000043414E46F6 -:108050004449666163653A204D65737361676520C5 -:1080600052414D204F766572666C6F77210000009B -:108070004261642043414E496661636520696E64D4 -:1080800065782E000000000000000000492B000869 -:10809000AD2300089D3200081D2400082924000893 -:1080A0006D280008CD250008E5230008E923000815 -:1080B000C1230008A923000829280008CD230008AF -:1080C00025340008D5330008D9230008FD2700080F -:1080D00001040E05054B02020E05054B04010E05B9 -:1080E000054B05010B04044B080106030346000081 -:1080F00010000240080002400008024000000B008F -:1081000028000240080002400408024006010C005A -:1081100040000240080002400808024010020D0022 -:1081200058000240080002400C08024016030E00EE -:10813000700002400C0002401008024000040F00D2 -:10814000880002400C00024014080240060510009E -:10815000A00002400C000240180802401006110066 -:10816000B80002400C0002401C08024016072F0015 -:1081700010040240080402402008024000083800B1 -:10818000280402400804024024080240060939007D -:10819000400402400804024028080240100A3A0045 -:1081A00058040240080402402C080240160B3B0011 -:1081B000700402400C04024030080240000C3C00F5 -:1081C000880402400C04024034080240060D4400BA -:1081D000A00402400C04024038080240100E450082 -:1081E000B80402400C0402403C080240160F46004E -:1081F00000960000000000000000000000000000E9 -:108200000000000000000000000000009D4E00087B -:10821000894E0008C54E0008B14E0008BD4E00084A -:10822000A94E0008954E0008814E0008D14E000866 -:1082300000000000B54F0008A14F0008DD4F000806 -:10824000C94F0008D54F0008C14F0008AD4F0008C6 -:10825000994F0008E94F00080000000001000000ED -:108260000000000063300000648200088854002091 -:10827000985600204172647550696C6F74002542F5 -:108280004F415244252D424C002553455249414C03 -:10829000250000000200000000000000D551000889 -:1082A0004552000840004000486F0020586F0020F1 -:1082B00002000000000000000300000000000000B9 -:1082C0008D5200080000000010000000686F0020C0 -:1082D0000000000001000000000000008872002083 -:1082E00001010200E15D0008F15C00088D5D0008FD -:1082F000715D000843000000FC8200080902430091 -:10830000020100C03209040000010202010005243C -:1083100000100105240100010424020205240600C6 -:1083200001070582030800FF09040100020A00009A -:10833000000705010240000007058102400000001F -:1083400012000000488300081201100102000040E2 -:10835000091241570002010203010000040309044D -:1083600025424F41524425003031323334353637BF -:1083700038394142434445460000000000010020D6 -:1083800000FF0100020000000000003000000400B7 -:1083900008000000000000240000080004000000A5 -:1083A0000004000000FC0000020000000000043097 -:1083B00000800000080000000000003800000100FC -:1083C0000100000000000000E9530008A156000869 -:1083D0004D57000840004000C0730020C0730020CB -:1083E00001000000D0730020800000004001000068 -:1083F000080000000001000000100000080000005C -:108400006D61696E0069646C650000000000802A7F -:1084100000000000AAAAAAAA00000024FFFF000092 -:108420000000000000A00A000000000000000000A2 -:10843000AAAAAAAA00000000FFFF00000000000096 -:10844000000000000000000000000000AAAAAAAA84 -:1084500000000000FFFF000000000000000000001E -:108460000A00000000000000AAAAAAAA000000005A -:10847000FFFF0000990000000000000000800200E3 -:1084800000000000AAAAAAAA00400100FFFF000005 -:108490000000007007000000000000000000000065 -:1084A000AAAAAAAA00000000FFFF00000000000026 -:1084B000000000000500000000000000A5AAAAAA14 -:1084C00000000000FCFF00000000000000000000B1 -:1084D0000000000000000000AAAAAAAA00000000F4 -:1084E000FFFF00000000000000000000000000008E -:1084F00000000000AAAAAAAA00000000FFFF0000D6 -:10850000000000000000000000000000000000006B -:10851000AAAAAAAA00000000FFFF000000000000B5 -:10852000000000000000000000000000AAAAAAAAA3 -:1085300000000000FFFF000000000000000000003D -:1085400037040000000000000000180000000000D8 -:10855000FE2A0100D2040000FF000000A056002007 -:10856000C44F002000000000FC7F000883040000CE -:1085700007800008500400001580000800960000E5 -:108580000000080096000000000800000400000041 -:108590005C830008000000000000000000000000F4 -:0C85A000000000000000000000000000CF +:1033C0000FB408B5029802F0CBFAFEE703F01AB882 +:1033D00002F0FCBF0139C9B202299EBF00EBC10057 +:1033E0000023C0E9013370472DE9F8431E461B88CE +:1033F000054688465B0718D4044600F118094C4579 +:1034000013D063686BB12B682846DB6B9847338811 +:10341000C1B2A76843F0040342466068B847083465 +:10342000EDE7A368002BEED1F9E70120BDE8F883B2 +:1034300073B56C4684E80600014600224E68D5B29A +:103440006EB98E685EB900EBC2000135021D94E8CA +:10345000030082E8030001201D7002B070BD01323C +:103460000831032AEAD10020F7E700002DE9F04FE8 +:103470002DED028B89B004468B460546BDF8508081 +:1034800000F11809002708F0040A9FED228BA945D6 +:1034900037D06B680BB9AB6863B1BAF1000F0BD1D1 +:1034A00023682046DB6B98474346C1B25A46D5E9AC +:1034B0000106B0470835EAE7002FFBD15B4603AAB7 +:1034C0000BF1080CADF808708DED008B186808330F +:1034D00053F8041C1746634503C73A46F6D11868EB +:1034E00038609B88BB800127FFF772FF0423ADF88B +:1034F00008302368CDE900011B6C694620469847D7 +:10350000D8E7012009B0BDEC028BBDE8F08F00BF09 +:10351000AFF300800000000000000000082817D969 +:1035200009280CD00A280CD00B280CD00C280CD061 +:103530000D280CD00E2814BF4020302070470C20DE +:1035400070471020704714207047182070472020C3 +:10355000704700002DE9F041456A15B94162BDE8A8 +:10356000F0814B68AC4623F06047C3F38A464FEACC +:10357000D37EC3F3807816EA230638BF3E462B4637 +:103580005A68BEEBD27F22F060440AD0002A18DAD3 +:10359000A40CB44217D19D420FD10D60DEE7134653 +:1035A000EEE7A74207D102F08044C2F380724245A1 +:1035B0000BD054B1EFE708D2EDE7CCF800100B6068 +:1035C000CDE7B44201D0B442E5D81A689C46002A3F +:1035D000E5D11960C3E700002DE9F047089D01F02F +:1035E000070400EBD1004FF47F494FEAD50822448D +:1035F00005F00705944201D1BDE8F08704F0070704 +:1036000005F0070A111B08EBD50E57453E4613F887 +:103610000EC038BF5646C6F108068E4228BF0E4679 +:10362000E108415C34443544B94029FA06F721FAEF +:103630000AF1FFB28CEA010147FA0AF739408CEA35 +:10364000010C03F80EC0D5E780EA0120082341F2FF +:10365000210201B2013B4000002980B2B8BF5040B6 +:1036600013F0FF03F5D1704738B50C468D18A5420D +:1036700000D138BD14F8011BFFF7E6FFF7E70000A3 +:1036800042684AB1136881894360438901339BB220 +:103690009942438138BF83811046704770B588B026 +:1036A000044620220D4668460021FEF777F92046A1 +:1036B0000495FFF7E5FF024660B16B46054608AE8C +:1036C0001C46083503CCB44245F8080C45F8041CE8 +:1036D0002346F5D1104608B070BD0000082817D960 +:1036E00009280CD00A280CD00B280CD00C280CD0A0 +:1036F0000D280CD00E2814BF4020302070470C201D +:103700007047102070471420704718207047202001 +:1037100070470000082817D90C280CD910280CD99C +:1037200014280CD918280CD920280CD930288CBF83 +:103730000F200E207047092070470A2070470B2089 +:1037400070470C2070470D20704700002DE9F843AA +:10375000078C0446072F1ED900254FF6FF73D0E9CA +:103760000298C5F12006A5F1200029FA05F10835D7 +:1037700008FA06F628FA00F0314301431846C9B2A8 +:10378000FFF762FF402D0346EBD13A46E169BDE801 +:10379000F843FFF769BF4FF6FF70BDE8F8830000FC +:1037A00010B54B6823B9CA8A63F30902CA8210BDF7 +:1037B00004691A681C600361C38A013BC3824A60C2 +:1037C000EFE700002DE9F84F1D46CB8A0F468146F2 +:1037D000C3F30901924605290B4630D00020AAB256 +:1037E00007F11A049EB21FFA80F8042E0FD89045F4 +:1037F00003F1010306D30A44FB8A62F309030120A3 +:10380000FB821AE01AF800600130E654EAE79045BE +:10381000F1D2A1F1050B1C237C68BBFBF3F203FB87 +:1038200012BB1FFA8BF6002C45D14846FFF728FF44 +:10383000044638B978606FF00200BDE8F88F4FF0A9 +:103840000008E6E7002606607860ADB24FF0000B96 +:10385000454510D90AEB0803221D13F8011B08F196 +:1038600001089155B1B21FFA88F81B292BD04545A4 +:1038700006F10106F1D8FB8AC3F30902154465F38A +:103880000903BCE701321C4692B22368002BF9D130 +:103890006B1F0B441C21B3FBF1F301339BB29A4223 +:1038A000D3D2BBF1000FD0D14846FFF7E9FE20B9D3 +:1038B000C4F800B0BFE70122E7E7C0F800B05E46F9 +:1038C00020600446C1E74545D5D94846FFF7D8FEF4 +:1038D00008B92060AFE7C0F800B0002620600446B9 +:1038E000B6E700002DE9F04F1C46074688462DED4F +:1038F000028B83B05B690192002B00F0A780238CC0 +:103900002BB1E269002A00F0A180072B35D807F11E +:103910000C00FFF7B5FE054638B96FF002052846E2 +:1039200003B0BDEC028BBDE8F08F14220021FEF73E +:1039300035F8228CE16905F10800FEF709F8208CC2 +:1039400048F00041013080B2FFF7E4FEFFF7C6FE09 +:10395000013880B220840130287438466369228C93 +:103960001B782A4403F01F0363F03F03137269605E +:103970002946FFF7EFFD0125D1E702330722C18A6F +:103980009BB20633B3FBF2F3828A9BB2521A92B215 +:103990009342C2D84FF0000900F10C034FF0800AA7 +:1039A0004E464D4608EE103A18EE100AFFF768FE34 +:1039B00083460028B1D014220021FDF7EFFF002E2E +:1039C0003AD1019B0222ABF808300BF1080E1FFA26 +:1039D00082FC218C0CF10100BCF1060F80B201D8F1 +:1039E0008E422BD3FFF796FE8E4208BF4FF0400A5F +:1039F000FFF774FE62690138013512781BFA80F115 +:103A0000013002F01F022DB242EA491289F0010989 +:103A10004AEA020A48F0004281F808A059468BF8A9 +:103A200010003846CBF804204FF0000AFFF792FD53 +:103A3000238CB342B8D172E70022C6E7E169895D01 +:103A400001360EF80210B6B20132C0E76FF0010580 +:103A500065E70000F8B515460E4630220021044601 +:103A60001F46FDF79BFF069BB5F5001FA76063602F +:103A700004F11000079B34BF6A094FF6FF72E6613C +:103A8000A362002397B29A4206D800230360A7825C +:103A9000E3822383E360F8BD0660013330462036BD +:103AA000F1E7000003781BB94BB2002BC8BF0170CF +:103AB0007047000000787047F8B50C46C9690746A2 +:103AC00011B9238C002B37D1257E1F2D34D838789F +:103AD00028BB228C072A2CD8268A36F003032BD148 +:103AE0004FF6FF70FFF7C0FD20F0010031024FF6E6 +:103AF000FF72400441EA0561400C41EA402523463B +:103B000029463846FFF7EEFE002807DD6269137884 +:103B10000133DBB21F2B88BF00231370F8BD218A4D +:103B20002D0645EA012505432046FFF70FFE024614 +:103B3000E5E76FF00300F1E76FF00100EEE700004A +:103B400070B58AB0044616460021282268461D46F4 +:103B5000FDF724FFBDF8383069462046ADF8103037 +:103B60000F9B05939DF840308DF81830119B0793FB +:103B7000BDF84830CDE90265ADF82030FFF79CFF75 +:103B80000AB070BD2DE9F041D36905460C461646D2 +:103B90000BB9138C5BBB377E1F2F28D895F800809C +:103BA000B8F1000F26D03046FFF7D0FD3378210260 +:103BB0000246284641EAC331338A41EA080141EA14 +:103BC000076141EA0341334641F08001FFF78AFE75 +:103BD00000280ADD3378012B07D17269137801338D +:103BE000DBB21F2B88BF00231370BDE8F0816FF09C +:103BF0000100FAE76FF00300F7E70000F0B58BB0C3 +:103C000004460D4617460021282268461E46FDF749 +:103C1000C5FE9DF84C30294620465A1E534253415A +:103C20006A468DF800309DF84030ADF81030119B99 +:103C300005939DF848308DF81830149B0793BDF814 +:103C40005430CDE90276ADF82030FFF79BFF0BB082 +:103C5000F0BD0000406A00B104307047436A1A6842 +:103C6000426202691A600361C38A013BC3827047E2 +:103C70002DE9F041D0F8208014461D46184E4146EB +:103C8000002709B9BDE8F081D1E90223A21A65EB4A +:103C90000303964277EB03031ED2036A8B420DD1D6 +:103CA000FFF77EFD036A1B68036203690B60C38A2A +:103CB0000161013B016AC3828846E2E7FFF770FDBC +:103CC0000B68C8F8003003690B60C38A0161013BCF +:103CD000C382D8F80010D4E788460968D1E700BF4E +:103CE00080841E002DE9F04F8BB00D4614469B4694 +:103CF000DDF850908046002800F01881B9F1000FDF +:103D000000F01481531E3F2B00F21081012A03D1D1 +:103D1000BBF1000F40F00A810023CDE90833B8F869 +:103D20001430B5EBC30F4FEAC30703D300200BB029 +:103D3000BDE8F08F2B199F42D8F80C3036BF7F1B9F +:103D40002746FFB21BB9D8F81030002B7AD0272DA8 +:103D50004DD8C5F1280600232946B742009308AB89 +:103D6000D8F808002CBFF6B23E46A7EB060A354449 +:103D700032465FFA8AFAFFF72FFCB8F81430282190 +:103D800003F10053053BDB000493D8F80C30039398 +:103D9000039B13B1BAF1000F2CD1D8F8100040B139 +:103DA000BAF1000F05D008AB5246691A0096FFF72A +:103DB00013FC38B2002FB9D066070AD00AAB6242B2 +:103DC00003EBD40102F0070211F8083C134101F89B +:103DD000083C082C3DD9102C40F2B580202C40F234 +:103DE000B780BBF1000F00F09C80082335E0BA4695 +:103DF0000026C2E7049BE02B28BFE02306930B4478 +:103E0000AB42059315D95A1B0398691A009692453F +:103E100008AB00F1040034BF5246D2B20792FFF75C +:103E2000DBFB079A1644AAEB020A1544F6B25FFAC6 +:103E30008AFA049B069A05999B1A0493039B1B68B4 +:103E40000393A5E700933A4608AB2946D8F8080043 +:103E5000ADE7BBF1000F13D00123B4EBC30F6BD060 +:103E6000082C12D89DF82030621E23FA02F2D507E2 +:103E700006D54FF0FF3202FA04F423438DF82030C8 +:103E80009DF8203089F8003051E7102C12D8BDF889 +:103E90002030621E23FA02F2D10706D54FF0FF321E +:103EA00002FA04F42343ADF82030BDF82030A9F81D +:103EB00000303CE7202C0FD80899631E21FA03F349 +:103EC000DA0705D54FF0FF3202FA04F40C430894E8 +:103ED000089BC9F800302AE7402C2AD0611EC4F1A3 +:103EE0002102A4F12103DDE9086526FA01F105FAB2 +:103EF00002F225FA03F311431943CB0711D501222E +:103F0000A4F12003C4F1200102FA03F322FA01F123 +:103F1000A2400B43524263EB430332432B43CDE9B0 +:103F20000823DDE90823C9E9002300E76FF0010059 +:103F3000FDE66FF00800FAE6082CA1D9102CB4D9E0 +:103F4000202CEED8C4E7BBF1000FAED0022384E7EB +:103F5000BBF1000FBCD004237FE70000012A30B57D +:103F6000144638BF012485B00025402C28BF4024CA +:103F7000012ACDE9025518D81B788DF8083063075F +:103F80000AD004AB624203EBD40502F0070215F835 +:103F9000083C934005F8083C034600912246002166 +:103FA00002A8FFF719FB05B030BD082AE4D9102A92 +:103FB00003D81B88ADF80830E1E7202A95BF1B68BD +:103FC000D3E900230293CDE90223D8E710B5CB68EB +:103FD0001BB98B600B618B8210BD04691A681C6071 +:103FE0000361C38A013BC382CA60F0E703064CBF8A +:103FF000C0F3C0300220704708B50246FFF7F6FF55 +:10400000022806D15306C2F30F2001D100F00300AD +:1040100008BDC2F30740FBE72DE9F04F93B004461B +:104020000D46CDE903230A681046FFF7DFFF02289B +:10403000824614BFC2F306260026002A80F2F881C9 +:1040400012F0C04940F0F481097B002900F0F081B2 +:10405000022803D02378B34240F0ED81C2F3046319 +:1040600010462944069302F07F030593FFF7C4FF2F +:10407000059B002283464FEA8348002348EA0A480A +:1040800048EA4668CE78CDE90823F30948EA0008F3 +:10409000029368D0059B024608A920460093534628 +:1040A0006768B847002800F0C981276A4FB94146C0 +:1040B00004F10C00FFF7F2FA074690B96FF0020026 +:1040C00055E03B6998450DD03F68002FF9D1414636 +:1040D00004F10C00FFF7E2FA07460028EED0236A4D +:1040E0003B60276297F817C006F01F08CCF3840CDA +:1040F000ACEB0800A8EB0C031FFA80FE0028B8BF49 +:104100000EF120001FFA83FEB8BF00B2002B079308 +:10411000B8BF0EF12003D7E90221BCBF1BB2079341 +:1041200052EA010338D0039B4FF0000CDFF81CE388 +:104130009A1A049B63EB010196457CEB01032BD398 +:104140006B7B97F81AE0734519D1029B002B78D04E +:10415000012821DC7868F8B9DFF8ECC2944570EBEF +:10416000010316D337E0276A27B96FF00C0013B0AC +:10417000BDE8F08F3B699845B4D03F68F4E7B2489A +:1041800090427CEB010301D30020F0E7029B002B5F +:10419000FAD0079B0F2B17DCFA7DB3003946204677 +:1041A00002F0030203F07C031343FB75FFF7F8FAF8 +:1041B0006B7BBB76029B3BB9FB7DC3F38402013270 +:1041C00062F38603FB75D0E76A7BBB7E9A42DBD144 +:1041D000029B002B35D0B309022B32D0039B142253 +:1041E00000210DA8BB60049BFB60FDF7D7FB039B80 +:1041F0000AA920460A93049BADF83EB00B932B1DF1 +:104200008DF840A00C932B7B8DF84180013BDBB2F5 +:10421000ADF83C30069B8DF84230059B8DF843305D +:1042200094F82C3083F001038DF84430A36898474C +:10423000FB7DC3F38403013303F01F039B02FB8266 +:10424000A2E7FB7DC6F34012B2EBD31F40F0F9802A +:10425000C3F38403434540F0FB80029AB6092B7BED +:10426000002A52D016F0010661D1032B40F2F380F0 +:10427000039B394604F10C00BB60049BFB60FB8A86 +:1042800066F30903AE1DFB8232462B7B033BDBB298 +:10429000FFF798FA00280CDA39462046FFF780FA33 +:1042A000FB7DC3F38403013303F01F039B02FB82F6 +:1042B00004E7AB88DDE908843B834FF6FF73C9F15F +:1042C0002000A9F1200228FA09F109F1080904FAED +:1042D00000F024FA02F2014318461143C9B2FFF775 +:1042E000B3F9B9F1400F0346E9D1B88231462A7BD0 +:1042F000033AD2B2FFF7B8F9FB7DB882DA43C2F3D2 +:10430000C01262F3C713FB753EE786B92E1D013B51 +:10431000394604F10C00DBB23246FFF753FA0028AD +:10432000BADB2A7B3146B88A013AD2B2E2E7F98A8F +:10433000013BC1F30901DAB204295BD8281D00232F +:1043400007F11B069A4208D910F801CB013306F891 +:1043500001C00131DBB20529F4D1039993420A91DE +:1043600038BF043304992CBF002355FA83F30B9113 +:1043700007F11B010C9179680E930D91291DFB8AA1 +:10438000ADF83EB0C3F309038DF840A08DF841802D +:104390001A44069B8DF84230059BADF83C208DF801 +:1043A000433094F82C3083F001038DF8443000231F +:1043B000B88A7B602A7B013AFFF756F93B8BB882BB +:1043C000834203D1A3680AA92046984720460AA938 +:1043D000FFF7FCFDFB7DBA8AC3F38403013303F0CE +:1043E0001F039B02FB823B8B9A420CBF00206FF0A5 +:1043F0001000BCE67B68002BAFD0052001E01C302C +:1044000033461E68002EFAD1091A2E1D081D1844C5 +:1044100001EB090C5FFA89F3BCF11B0F9DD89A429E +:104420009BD916F8013B09F1010900F8013BEFE7C0 +:104430006FF009009BE66FF00A0098E66FF00B0042 +:1044400095E66FF00D0092E640420F0080841E005A +:104450006FF00E008BE66FF00F0088E6EFF3098334 +:10446000054968334A6B22F001024A6383F30988E5 +:10447000002383F31188704700EF00E0302080F3C1 +:10448000118862B60D4B0E4AD96821F4E061090427 +:10449000090C0A430B49DA60D3F8FC2042F0807221 +:1044A000C3F8FC20084AC2F8B01F116841F00101AE +:1044B00011602022DA7783F82200704700ED00E0D7 +:1044C0000003FA0555CEACC5001000E0302310B54E +:1044D00083F311880E4B5B6813F4006314D0F1EE84 +:1044E000103AEFF309844FF08073683CE361094BA5 +:1044F000DB6B236684F3098801F0F8F910B1064BF1 +:10450000A36110BD054BFBE783F31188F9E700BFFA +:1045100000ED00E000EF00E03F0400084204000866 +:1045200008B5074B074A196801F03D0199605368C7 +:104530000BB190689847BDE80840FFF7C7BF00BFC0 +:1045400000000240404F002008B5084B1968890957 +:1045500001F03D018A019A60054AD3680BB11069E8 +:104560009847BDE80840FFF7B1BF00BF0000024018 +:10457000404F002008B5084B1968090C01F03D01B7 +:104580000A049A60054A53690BB190699847BDE8DF +:104590000840FFF79BBF00BF00000240404F0020D3 +:1045A00008B5084B1968890D01F03D018A059A602C +:1045B000054AD3690BB1106A9847BDE80840FFF778 +:1045C00085BF00BF00000240404F002008B5074BE8 +:1045D000074A596801F03D01D960536A0BB1906AEE +:1045E0009847BDE80840FFF771BF00BF00000240D8 +:1045F000404F002008B5084B5968890901F03D017A +:104600008A01DA60054AD36A0BB1106B9847BDE89E +:104610000840FFF75BBF00BF00000240404F002092 +:1046200008B5084B5968090C01F03D010A04DA602D +:10463000054A536B0BB1906B9847BDE80840FFF7F4 +:1046400045BF00BF00000240404F002008B5084BA6 +:104650005968890D01F03D018A05DA60054AD36B7E +:104660000BB1106C9847BDE80840FFF72FBF00BFA3 +:1046700000000240404F002008B5074B074A196868 +:1046800001F03D019960536C0BB1906C9847BDE807 +:104690000840FFF71BBF00BF00040240404F00204E +:1046A00008B5084B1968890901F03D018A019A6033 +:1046B000054AD36C0BB1106D9847BDE80840FFF771 +:1046C00005BF00BF00040240404F002008B5084B62 +:1046D0001968090C01F03D010A049A60054A536DFE +:1046E0000BB1906D9847BDE80840FFF7EFBE00BFE3 +:1046F00000040240404F002008B5084B1968890D9E +:1047000001F03D018A059A60054AD36D0BB1106E28 +:104710009847BDE80840FFF7D9BE00BF000402403B +:10472000404F002008B5074B074A596801F03D018A +:10473000D960536E0BB1906E9847BDE80840FFF703 +:10474000C5BE00BF00040240404F002008B5084B22 +:104750005968890901F03D018A01DA60054AD36E82 +:104760000BB1106F9847BDE80840FFF7AFBE00BF20 +:1047700000040240404F002008B5084B5968090C5E +:1047800001F03D010A04DA60054A536F0BB1906FE6 +:104790009847BDE80840FFF799BE00BF00040240FB +:1047A000404F002008B5084B5968890D01F03D01C4 +:1047B0008A05DA60054AD36F13B1D2F880009847B2 +:1047C000BDE80840FFF782BE00040240404F0020D1 +:1047D00000230C4910B51A460B4C0B6054F823000B +:1047E000026001EB430004334260402BF6D1074ADC +:1047F0004FF0FF339360D360C2F80834C2F80C3432 +:1048000010BD00BF404F002008810008000002409A +:104810000F28F8B510D9102810D0112811D012285F +:1048200008D10F240720DFF8B4E00126DEF800509D +:10483000A04208D9002649E00446F4E70F240020EE +:10484000F1E70724FBE706FA00F73D4240D1214C8F +:104850004FEA001C3D4304EB00160EEBC000CEF8FF +:104860000050C0E90123FBB24BB11B48836B43F0FE +:1048700001038363036E43F001030366036E17F4C1 +:104880007F4F09D01448836B43F002038363036EA8 +:1048900043F002030366036E54F80C00036823F030 +:1048A0001F030360056815F00105FBD104EB0C0341 +:1048B0003D2493F80CC05F6804FA0CF43C6021249A +:1048C0000560446112B1987B00F056F93046F8BD9E +:1048D0000130ADE70881000800450258404F002034 +:1048E00010B5302484F31188FFF792FF002383F37F +:1048F000118810BD10B50446807B00F053F90123E8 +:104900001049627B03FA02F20B6823EA0203DAB26F +:104910000B604AB90C4A916B21F001019163116E51 +:1049200021F001011166126E13F47F4F09D1064B7D +:104930009A6B22F002029A631A6E22F002021A6641 +:104940001B6E10BD404F00200045025808B53023B3 +:1049500083F31188FFF7CEFF002383F3118808BD8E +:10496000026843681143016003B1184770470000B3 +:10497000024A136843F0C003136070470078004098 +:1049800013B50E4C204600F0B7FA04F114000023D2 +:104990004FF400720A49009400F074F9094B4FF487 +:1049A0000072094904F13800009400F0EDF9074A5B +:1049B000074BC4E9172302B010BD00BFC44F00204D +:1049C000305000207149000830520020007800402B +:1049D00000E1F505037C30B5214C002918BF0C46D9 +:1049E000012B0CD11F4B984209D11F4B9A6C42F0FE +:1049F00080429A641A6F42F080421A671B6F2268E5 +:104A0000036EC16D03EB52038466B3FBF2F362687D +:104A1000150442BF23F0070503F0070343EA4503EB +:104A2000CB60A36843F040034B60E36843F00103AD +:104A30008B6042F4967343F001030B604FF0FF3339 +:104A40000B62510505D512F0102205D0B2F1805F3E +:104A500004D080F8643030BD7F23FAE73F23F8E7C5 +:104A600008820008C44F0020004502582DE9F04795 +:104A7000C66D05463768F469210734621AD014F010 +:104A8000080118BF4FF48071E20748BF41F02001D0 +:104A9000A3074FF0300348BF41F04001600748BF13 +:104AA00041F0800183F31188281DFFF759FF00238F +:104AB00083F31188E2050AD5302383F311884FF47C +:104AC0008061281DFFF74CFF002383F311884FF00E +:104AD00030094FF0000A14F0200838D13B0616D5F3 +:104AE0004FF0300905F1380A200610D589F31188F6 +:104AF000504600F07DF9002836DA0821281DFFF71E +:104B00002FFF27F080033360002383F31188790699 +:104B100014D5620612D5302383F31188D5E9132307 +:104B20009A4208D12B6C33B127F040071021281D81 +:104B3000FFF716FF3760002383F31188E30618D5CB +:104B4000AA6E1369ABB15069BDE8F047184789F305 +:104B50001188736A284695F86410194000F0E6F948 +:104B60008AF31188F469B6E7B06288F31188F469B2 +:104B7000BAE7BDE8F0870000090100F160430122B7 +:104B800003F56143C9B283F8001300F01F039A4094 +:104B900043099B0003F1604303F56143C3F880219F +:104BA0001A60704700F01F0301229A40430900F188 +:104BB00060409B0000F5614003F1604303F56143F1 +:104BC000C3F88020C3F88021002380F800337047A9 +:104BD000F8B51546826804460B46AA4200D285689D +:104BE000A1692669761AB5420BD218462A46FCF707 +:104BF000AFFEA3692B44A3612846A3685B1BA36097 +:104C0000F8BD0CD9AF1B18463246FCF7A1FE3A4658 +:104C1000E1683044FCF79CFEE3683B44EBE7184650 +:104C20002A46FCF795FEE368E5E7000083689342B7 +:104C3000F7B50446154600D28568D4E90460361AF3 +:104C4000B5420BD22A46FCF783FE63692B446361AD +:104C50002846A3685B1BA36003B0F0BD0DD93246A4 +:104C6000AF1B0191FCF774FE01993A46E0683144AC +:104C7000FCF76EFEE3683B44E9E72A46FCF768FE72 +:104C8000E368E4E710B50A440024C361029B846032 +:104C9000C16002610362C0E90000C0E9051110BDF6 +:104CA00008B5D0E90532934201D1826882B98268A1 +:104CB000013282605A1C426119700021D0E904322D +:104CC0009A4224BFC368436100F0C0FE002008BDC3 +:104CD0004FF0FF30FBE7000070B5302304460E466E +:104CE00083F31188A568A5B1A368A269013BA360FD +:104CF000531CA36115782269934224BFE368A36122 +:104D0000E3690BB120469847002383F311882846B6 +:104D100007E03146204600F089FE0028E2DA85F3FC +:104D2000118870BD2DE9F74F04460E461746984688 +:104D3000D0F81C904FF0300A8AF311884FF0000B26 +:104D4000154665B12A4631462046FFF741FF034626 +:104D500060B94146204600F069FE0028F1D00023EA +:104D600083F31188781B03B0BDE8F08FB9F1000F11 +:104D700003D001902046C847019B8BF31188ED1AA0 +:104D80001E448AF31188DCE7C160C361009B826026 +:104D90000362C0E905111144C0E9000001617047D8 +:104DA000F8B504460D461646302383F31188A768EC +:104DB000A7B1A368013BA36063695A1C62611D70BF +:104DC000D4E904329A4224BFE3686361E3690BB11A +:104DD00020469847002080F3118807E0314620469E +:104DE00000F024FE0028E2DA87F31188F8BD000005 +:104DF000D0E9052310B59A4201D182687AB9826858 +:104E00000021013282605A1C82611C7803699A4237 +:104E100024BFC368836100F019FE204610BD4FF027 +:104E2000FF30FBE72DE9F74F04460E46174698463C +:104E3000D0F81C904FF0300A8AF311884FF0000B25 +:104E4000154665B12A4631462046FFF7EFFE034678 +:104E500060B94146204600F0E9FD0028F1D000236A +:104E600083F31188781B03B0BDE8F08FB9F1000F10 +:104E700003D001902046C847019B8BF31188ED1A9F +:104E80001E448AF31188DCE702684368114301601D +:104E900003B11847704700001430FFF743BF00000C +:104EA0004FF0FF331430FFF73DBF00003830FFF7FD +:104EB000B9BF00004FF0FF333830FFF7B3BF000039 +:104EC0001430FFF709BF00004FF0FF311430FFF737 +:104ED00003BF00003830FFF763BF00004FF0FF3220 +:104EE0003830FFF75DBF0000012914BF6FF01300D9 +:104EF00000207047FFF744BD044B0360002343606C +:104F0000C0E9023301230374704700BF2082000808 +:104F100010B53023044683F31188FFF75BFD0223AD +:104F20000020237480F3118810BD000038B5C369D8 +:104F300004460D461BB904210844FFF7A5FF294686 +:104F400004F11400FFF7ACFE002806DA201D4FF430 +:104F50000061BDE83840FFF797BF38BD026843687D +:104F60001143016003B118477047000013B5406B4F +:104F700000F58054D4F8A4381A681178042914D1A3 +:104F8000017C022911D11979012312898B40134226 +:104F90000BD101A94C3002F0F3F9D4F8A448024631 +:104FA000019B2179206800F0DFF902B010BD0000FC +:104FB000143002F075B900004FF0FF33143002F0E6 +:104FC0006FB900004C3002F047BA00004FF0FF33D9 +:104FD0004C3002F041BA0000143002F043B9000036 +:104FE0004FF0FF31143002F03DB900004C3002F0B8 +:104FF00013BA00004FF0FF324C3002F00DBA00003F +:105000000020704710B500F58054D4F8A4381A6811 +:105010001178042917D1017C022914D1597901236F +:1050200052898B4013420ED1143002F0D5F802465B +:1050300048B1D4F8A4484FF4407361792068BDE8C2 +:10504000104000F07FB910BD406BFFF7DBBF0000E0 +:10505000704700007FB5124B01250426044603600B +:105060000023057400F1840243602946C0E902333D +:105070000C4B0290143001934FF44073009602F0F1 +:1050800087F8094B04F69442294604F14C00029437 +:10509000CDE900634FF4407302F04EF904B070BDE7 +:1050A00048820008495000086D4F00080A68302304 +:1050B00083F311880B790B3342F823004B791333B8 +:1050C00042F823008B7913B10B3342F8230000F52B +:1050D0008053C3F8A41802230374002080F31188BE +:1050E0007047000038B5037F044613B190F8543080 +:1050F000ABB90125201D0221FFF730FF04F1140098 +:105100006FF00101257700F0ADFC04F14C0084F84C +:1051100054506FF00101BDE8384000F0A3BC38BD29 +:1051200010B5012104460430FFF718FF0023237750 +:1051300084F8543010BD000038B504460025143002 +:1051400002F03EF804F14C00257702F00DF9201D25 +:1051500084F854500121FFF701FF2046BDE8384094 +:10516000FFF750BF90F8803003F06003202B06D18A +:1051700090F881200023212A03D81F2A06D8002076 +:105180007047222AFBD1C0E91D3303E0034A42677E +:1051900007228267C3670120704700BF3C230020BD +:1051A00037B500F58055D5F8A4381A681178042968 +:1051B0001AD1017C022917D11979012312898B4058 +:1051C000134211D100F14C04204602F08DF958B180 +:1051D00001A9204602F0D4F8D5F8A4480246019B64 +:1051E0002179206800F0C0F803B030BD01F10B0355 +:1051F000F0B550F8236085B004460D46FEB130236B +:1052000083F3118804EB8507301D0821FFF7A6FE04 +:10521000FB6806F14C005B691B681BB1019002F052 +:10522000BDF8019803A902F0ABF8024648B1039B10 +:105230002946204600F098F8002383F3118805B032 +:10524000F0BDFB685A691268002AF5D01B8A013B41 +:105250001340F1D104F18002EAE70000133138B5C0 +:1052600050F82140ECB1302383F3118804F58053CA +:10527000D3F8A4281368527903EB8203DB689B6997 +:105280005D6845B104216018FFF768FE294604F106 +:10529000140001F0ABFF2046FFF7B4FE002383F3B8 +:1052A000118838BD7047000001F07EBA012340220A +:1052B000002110B5044600F8303BFCF76FFB0023DB +:1052C000C4E9013310BD000010B53023044683F358 +:1052D00011882422416000210C30FCF75FFB20463E +:1052E00001F084FA02230020237080F3118810BD9E +:1052F00070B500EB8103054650690E461446DA602E +:1053000018B110220021FCF749FBA06918B1102246 +:105310000021FCF743FB31462846BDE8704001F010 +:1053200065BB000083682022002103F0011310B543 +:10533000044683601030FCF731FB2046BDE8104086 +:1053400001F0E0BBF0B4012500EB810447898D40FA +:10535000E4683D43A469458123600023A260636043 +:10536000F0BC01F0FDBB0000F0B4012500EB8104AE +:1053700007898D40E4683D4364690581236000230B +:10538000A2606360F0BC01F073BC000070B5022342 +:1053900000250446242203702946C0F888500C30AA +:1053A00040F8045CFCF7FAFA204684F8705001F0EB +:1053B000B1FA63681B6823B129462046BDE87040F6 +:1053C000184770BD0378052B10B504460AD080F845 +:1053D0008C300523037043681B680BB10421984788 +:1053E0000023A36010BD00000178052906D190F8C4 +:1053F0008C20436802701B6803B118477047000097 +:1054000070B590F87030044613B1002380F8703006 +:1054100004F18002204601F099FB63689B68B3B9F0 +:1054200094F8803013F0600535D00021204601F05B +:105430008BFE0021204601F07BFE63681B6813B1E0 +:10544000062120469847062384F8703070BD204618 +:1054500098470028E4D0B4F88630A26F9A4288BFFB +:10546000A36794F98030A56F002B4FF0300380F2D2 +:105470000381002D00F0F280092284F8702083F36C +:10548000118800212046D4E91D23FFF76DFF00237A +:1054900083F31188DAE794F8812003F07F0343EA6D +:1054A000022340F20232934200F0C58021D8B3F5C6 +:1054B000807F48D00DD8012B3FD0022B00F0938085 +:1054C000002BB2D104F1880262670222A267E3676F +:1054D000C1E7B3F5817F00F09B80B3F5407FA4D195 +:1054E00094F88230012BA0D1B4F8883043F0020345 +:1054F00032E0B3F5006F4DD017D8B3F5A06F31D0BF +:10550000A3F5C063012B90D86368204694F88220ED +:105510005E6894F88310B4F88430B047002884D0D3 +:10552000436863670368A3671AE0B3F5106F36D06A +:1055300040F6024293427FF478AF5C4B63670223EC +:10554000A3670023C3E794F88230012B7FF46DAF8B +:10555000B4F8883023F00203A4F88830C4E91D555C +:10556000E56778E7B4F88030B3F5A06F0ED194F812 +:105570008230204684F88A3001F02AFA63681B687A +:1055800013B1012120469847032323700023C4E967 +:105590001D339CE704F18B0363670123C3E7237882 +:1055A000042B10D1302383F311882046FFF7BAFE75 +:1055B00085F311880321636884F88B5021701B6880 +:1055C0000BB12046984794F88230002BDED084F847 +:1055D0008B300423237063681B68002BD6D0022114 +:1055E00020469847D2E794F8843020461D0603F001 +:1055F0000F010AD501F09CFA012804D002287FF49B +:1056000014AF2B4B9AE72B4B98E701F083FAF3E7A3 +:1056100094F88230002B7FF408AF94F8843013F0B4 +:105620000F01B3D01A06204602D501F0A5FDADE763 +:1056300001F096FDAAE794F88230002B7FF4F5AED6 +:1056400094F8843013F00F01A0D01B06204602D539 +:1056500001F07AFD9AE701F06BFD97E7142284F8D8 +:10566000702083F311882B462A4629462046FFF7EF +:1056700069FE85F31188E9E65DB1152284F8702092 +:1056800083F3118800212046D4E91D23FFF75AFE39 +:10569000FDE60B2284F8702083F311882B462A46FE +:1056A00029462046FFF760FEE3E700BF7882000846 +:1056B000708200087482000838B590F87030044693 +:1056C000002B3ED0063BDAB20F2A34D80F2B32D84B +:1056D000DFE803F0373131082232313131313131F5 +:1056E00031313737856FB0F886309D4214D2C368A8 +:1056F0001B8AB5FBF3F203FB12556DB9302383F31C +:1057000011882B462A462946FFF72EFE85F311887D +:105710000A2384F870300EE0142384F870303023AC +:1057200083F31188002320461A461946FFF70AFE24 +:10573000002383F3118838BDC36F03B1984700235A +:10574000E7E70021204601F0FFFC0021204601F0A0 +:10575000EFFC63681B6813B10621204698470623B7 +:10576000D7E7000010B590F870300446142B29D00C +:1057700017D8062B05D001D81BB110BD093B022B51 +:10578000FBD80021204601F0DFFC0021204601F07B +:10579000CFFC63681B6813B1062120469847062397 +:1057A00019E0152BE9D10B2380F87030302383F3F7 +:1057B000118800231A461946FFF7D6FD002383F30C +:1057C0001188DAE7C3689B695B68002BD5D1C36F8A +:1057D00003B19847002384F87030CEE70023826835 +:1057E000037503691B6899689142FBD25A6803608C +:1057F0004260106058607047002382680375036937 +:105800001B6899689142FBD85A6803604260106037 +:105810005860704708B50846302383F311880A7D25 +:105820000023052A06D8DFE802F00B050503120E57 +:10583000826913604FF0FF338361FFF7CFFF0023CE +:1058400083F3118808BD8269936801339360D0E9BE +:10585000003213605A60EDE7FFF7C0BF054BD9680F +:1058600008751868026853601A600122D8600275D2 +:10587000FAF7D0BD305400200C4B30B5DD684B1C1E +:1058800087B004460FD02B46094A684600F07EF9DF +:105890002046FFF7E3FF009B13B1684600F080F954 +:1058A000A86907B030BDFFF7D9FFF9E730540020F1 +:1058B0001558000838B50C4D04468161EB688168C5 +:1058C0009A68914203D8BDE83840FFF787BF184671 +:1058D000FFF792FF01230146EC6020462375BDE8E7 +:1058E0003840FAF797BD00BF30540020044B1A68C7 +:1058F000DB6890689B68984294BF00200120704745 +:1059000030540020084B10B51C68D86822685360DA +:105910001A600122DC602275FFF76EFF0146204607 +:10592000BDE81040FAF776BD3054002038B50123A9 +:10593000084C00252370656001F012FE01F038FE6E +:105940000549064801F00CFF0223237085F31188F6 +:1059500038BD00BF985600208082000830540020D7 +:1059600008B572B6044B186500F022FD00F0E4FDA6 +:10597000024B03221A70FEE7305400209856002094 +:1059800000F044B9034A516853685B1A9842FBD847 +:10599000704700BF001000E08B60022308610846DA +:1059A0008B8270478368A3F1840243F8142C026948 +:1059B00043F8442C426943F8402C094A43F8242C0C +:1059C000C268A3F1200043F8182C022203F80C2C23 +:1059D000002203F80B2C034A43F8102C704700BF39 +:1059E0002D0400083054002008B5FFF7DBFFBDE8A8 +:1059F0000840FFF731BF0000024BDB6898610F20C1 +:105A0000FFF72CBF30540020302383F31188FFF7B9 +:105A1000F3BF000008B50146302383F31188082046 +:105A2000FFF72AFF002383F3118808BD064BDB68CC +:105A300039B1426818605A60136043600420FFF770 +:105A40001BBF4FF0FF30704730540020036898426E +:105A500006D01A680260506018469961FFF7FCBED4 +:105A60007047000038B504460D462068844200D1D6 +:105A700038BD036823605C608561FFF7EDFEF4E7E5 +:105A8000036810B59C68A2420CD85C688A600B6001 +:105A90004C602160596099688A1A9A604FF0FF3310 +:105AA000836010BD121B1B68ECE700000A2938BF99 +:105AB0000A2170B504460D460A26601901F04AFD18 +:105AC00001F032FD041BA54203D8751C04462E4686 +:105AD000F3E70A2E04D90120BDE8704001F080BE32 +:105AE00070BD0000F8B5144B0D460A2A4FF00A07A6 +:105AF000D96103F11001826038BF0A22416019693F +:105B00001446016048601861A81801F013FD01F007 +:105B10000BFD431B0646A34206D37C1C28192746CF +:105B2000354601F017FDF2E70A2F04D90120BDE840 +:105B3000F84001F055BEF8BD30540020F8B50646D7 +:105B40000D4601F0F1FC0F4A134653F8107F9F42B7 +:105B500006D12A4601463046BDE8F840FFF7C2BFED +:105B6000D169BB68441A2C1928BF2C46A34202D91C +:105B70002946FFF79BFF224631460348BDE8F8401F +:105B8000FFF77EBF3054002040540020C0E90323BB +:105B9000002310B45DF8044B4361FFF7CFBF000052 +:105BA00010B5194C236998420DD08168D0E90032B4 +:105BB00013605A609A680A449A60002303604FF0A9 +:105BC000FF33A36110BD0268234643F8102F5360D2 +:105BD0000022026022699A4203D1BDE8104001F020 +:105BE000B3BC936881680B44936001F09DFC22690B +:105BF000E1699268441AA242E4D91144BDE8104018 +:105C0000091AFFF753BF00BF305400202DE9F047B9 +:105C1000DFF8BC8008F110072C4ED8F8105001F0C6 +:105C200083FCD8F81C40AA68031B9A423ED814444F +:105C30004FF00009D5E90032C8F81C4013605A60E3 +:105C4000C5F80090D8F81030B34201D101F07CFCC7 +:105C500089F31188D5E9033128469847302383F327 +:105C600011886B69002BD8D001F05EFC6A69A0EB4B +:105C7000040982464A450DD2022001F0B1FD0022FE +:105C8000D8F81030B34208D151462846BDE8F04755 +:105C9000FFF728BF121A2244F2E712EB090929463E +:105CA000384638BF4A46FFF7EBFEB5E7D8F8103064 +:105CB000B34208D01444C8F81C00211AA960BDE8FA +:105CC000F047FFF7F3BEBDE8F08700BF4054002067 +:105CD0003054002038B501F027FC054AD2E90845C8 +:105CE000031B181945F10001C2E9080138BD00BFC6 +:105CF0003054002000207047FEE70000704700008D +:105D00004FF0FF307047000002290CD0032904D067 +:105D10000129074818BF00207047032A05D8054805 +:105D200000EBC2007047044870470020704700BF76 +:105D3000588300084C2300200C83000870B59AB0EB +:105D400005460846144601A900F0C2F801A8FBF771 +:105D50001DFE431C0022C6B25B001046C5E900349C +:105D600023700323023404F8013C01ABD1B20234A6 +:105D70008E4201D81AB070BD13F8011B013204F82D +:105D8000010C04F8021CF1E708B5302383F31188F5 +:105D90000348FFF705FA002383F3118808BD00BF0D +:105DA000A056002090F8803003F01F02012A07D18E +:105DB00090F881200B2A03D10023C0E91D3315E0A0 +:105DC00003F06003202B08D1B0F884302BB990F891 +:105DD0008120212A03D81F2A04D8FFF7C3B9222A19 +:105DE000EBD0FAE7034A426707228267C3670120C4 +:105DF000704700BF4323002007B5052917D8DFE807 +:105E000001F0191603191920302383F31188104A61 +:105E100001210190FFF76CFA019802210D4AFFF76A +:105E200067FA0D48FFF788F9002383F3118803B060 +:105E30005DF804FB302383F311880748FFF752F91C +:105E4000F2E7302383F311880348FFF769F9EBE7A2 +:105E5000AC820008D0820008A056002038B50C4D56 +:105E60000C4C2A460C4904F10800FFF767FF05F1C6 +:105E7000CA0204F110000949FFF760FF05F5CA7274 +:105E800004F118000649BDE83840FFF757BF00BFCE +:105E9000786F00204C2300208C8200089682000836 +:105EA000A182000870B5044608460D46FBF76EFD5A +:105EB000C6B22046013403780BB9184670BD32468D +:105EC0002946FBF74FFD0028F3D10120F6E700003B +:105ED0002DE9F84F05460C46FBF758FD2A49C6B296 +:105EE0002846FFF7DFFF08B10136F6B227492846FA +:105EF000FFF7D8FF08B11036F6B2632E0DD8DFF8E1 +:105F00008890DFF888A0224FDFF88CB0DFF88C8013 +:105F10002E7846B92670BDE8F88F29462046BDE8A0 +:105F2000F84F02F063B8252E2AD1072249462846A9 +:105F3000FBF718FD50B9D8F800300735083444F89D +:105F4000083CD8F8043044F8043CE1E70822514604 +:105F50002846FBF707FD98B9A21C0E4B19780232B0 +:105F60000909C95D02F8041C13F8011B01F00F01B7 +:105F70005B45C95D02F8031CF0D118340835C7E74A +:105F8000013504F8016BC3E778830008A18200089B +:105F90008083000800E8F11F0CE8F11F0A80000868 +:105FA000BFF34F8F044B1A695107FCD1D3F810216E +:105FB0005207F8D1704700BF0020005208B50D4BC2 +:105FC0001B78ABB9FFF7ECFF0B4BDA68D10704D5B0 +:105FD0000A4A5A6002F188325A60D3F80C21D2077B +:105FE00006D5064AC3F8042102F18832C3F8042119 +:105FF00008BD00BFD6710020002000522301674574 +:1060000008B5114B1B78F3B9104B1A69510703D52A +:10601000DA6842F04002DA60D3F81021520705D561 +:10602000D3F80C2142F04002C3F80C21FFF7B8FF6F +:10603000064BDA6842F00102DA60D3F80C2142F034 +:106040000102C3F80C2108BDD671002000200052C7 +:106050000F289ABF00F580604004002070470000C0 +:106060004FF4003070470000102070470F2808B52B +:106070000BD8FFF7EDFF00F500330268013204D1C1 +:1060800004308342F9D1012008BD0020FCE7000064 +:106090000F2838B505463FD8FFF782FF1F4CFFF7A2 +:1060A0008DFF4FF0FF3307286361C4F814311DD80A +:1060B0002361FFF775FF030243F02403E360E36805 +:1060C00043F08003E36023695A07FCD42846FFF7B6 +:1060D00067FFFFF7BDFF4FF4003100F009FA2846D3 +:1060E000FFF78EFFBDE83840FFF7C0BFC4F810319E +:1060F000FFF756FFA0F108031B0243F02403C4F886 +:106100000C31D4F80C3143F08003C4F80C31D4F8CE +:1061100010315B07FBD4D9E7002038BD00200052C6 +:106120002DE9F84F05460C46104645EA0203DE0607 +:1061300002D00020BDE8F88F20F01F00DFF8BCB0CF +:10614000DFF8BCA0FFF73AFF04EB0008444503D199 +:106150000120FFF755FFEDE720222946204601F0F8 +:1061600013FF10B920352034F0E72B4605F120024B +:106170001F68791CDDD104339A42F9D105F17843C7 +:106180001B481C4EB3F5801F1B4B38BF184603F14C +:10619000F80332BFD946D1461E46FFF701FF07601C +:1061A000A5EB040C336804F11C0143F002033360D7 +:1061B000231FD9F8007017F00507FAD153F8042F00 +:1061C0008B424CF80320F4D1BFF34F8FFFF7E8FE6A +:1061D0004FF0FF332022214603602846336823F026 +:1061E0000203336001F0D0FE0028BBD03846B0E790 +:1061F000142100520C200052142000521020005292 +:106200001021005210B5084C237828B11BB9FFF7B4 +:10621000D5FE0123237010BD002BFCD02070BDE8FB +:106220001040FFF7EDBE00BFD67100202DE9F04F02 +:106230000D4685B0814658B111F00D0614BF2022DD +:10624000082211F00803019304D0431E03426AD0D0 +:10625000002435E0002E37D009F11F0121F01F097D +:106260004FF00108324F05F00403DFF8D0A005EA33 +:10627000080BBBF1000F32D07869C0072FD408F1AA +:1062800001080C37B8F1060FF3D19EB9294D4946E4 +:10629000A819019201F0AEF9044600283AD1183647 +:1062A000019A782EF3D1494601F0A4F9044600285A +:1062B00030D1019A4946204801F09CF9044668BB58 +:1062C000204605B0BDE8F08F0029C9D10146284617 +:1062D000029201F08FF90446E0B9029AC0E713B1C7 +:1062E00078694107CBD5AC0702D578698007C6D558 +:1062F000019911B178690107C1D51820494600FB01 +:1063000008A0CDE9022301F075F90446DDE9022376 +:106310000028B4D04A460021204601E04A46002128 +:10632000FBF73CFBCCE70246002E95D198E700BF77 +:106330009483000808720020D8710020F0710020BA +:106340000121FFF773BF0000F8B5144D0124182791 +:10635000134E40F2FF3200210120FBF71FFB07FB29 +:10636000046001342A6955F80C1F01F02FF9062C3E +:10637000F5D137254FF4C0542046FFF7E1FF014621 +:1063800028B122460748BDE8F84001F01FB9C4EB28 +:10639000C404013D4FEAD404EED1F8BD9483000853 +:1063A000F0710020D871002008B101F095B9704754 +:1063B00038B5054D00240334696855F80C0B00F01E +:1063C000A9F8122CF7D138BD9483000838B5EFF343 +:1063D00011859DB9EFF30584C4F30804302334B16B +:1063E00083F31188FFF776FC85F3118838BD83F3BA +:1063F0001188FFF76FFC84F3118838BDBDE8384081 +:10640000FFF768BC10B5FFF7E1FF104CC008104A59 +:10641000002340EA4170C908A0FB04ECA0FB020E77 +:106420001CEB0000A1FB044CA1FB02125B41001914 +:1064300043EB0C0011EB0E0142F10002411842F156 +:106440000000090941EA007010BD00BFCFF753E317 +:10645000A59BC4200244074BD2B210B5904200D194 +:1064600010BD441C00B253F8200041F8040BE0B208 +:10647000F4E700BF504000580E4B30B51C6F2404A9 +:1064800005D41C6F1C671C6F44F400441C670A4C45 +:1064900002442368D2B243F480732360074B9042D6 +:1064A00000D130BD441C51F8045B00B243F82050C9 +:1064B000E0B2F4E700440258004802585040005847 +:1064C00007B5012201A90020FFF7C4FF019803B01E +:1064D0005DF804FB13B50446FFF7F2FFA04205D0B8 +:1064E000012201A900200194FFF7C6FF02B010BDF0 +:1064F0000144BFF34F8F064B884204D3BFF34F8F45 +:10650000BFF36F8F7047C3F85C022030F4E700BF21 +:1065100000ED00E00144BFF34F8F064B884204D3E7 +:10652000BFF34F8FBFF36F8F7047C3F870022030F7 +:10653000F4E700BF00ED00E070470000114BDA699E +:1065400052021ED59A69D00704D50F4A9A6002F10B +:1065500044329A600B4BDA69D107FCD41A6A22F4F0 +:1065600080021A629A6942F002029A61DA69D207DD +:10657000FCD49A6942F001029A61024AD369DB07AE +:10658000FCD47047002000523B2A1908074B45F203 +:1065900055521A6003225A6040F2FF729A604CF61C +:1065A000CC421A600122024B1A7070470048005812 +:1065B00084720020034B1B781BB1034B4AF6AA22BE +:1065C0001A6070478472002000480058034B1A6814 +:1065D0001AB9034AD2F8D0241A607047807200209A +:1065E00000400258024B4FF48032C3F8D024704769 +:1065F0000040025808B5FFF7E9FF024B1868C0F3E6 +:10660000806008BD8072002070B5BFF34F8FBFF36C +:106610006F8F1A4A0021C2F85012BFF34F8FBFF399 +:106620006F8F536943F400335361BFF34F8FBFF350 +:106630006F8FC2F88410BFF34F8FD2F8803043F6CB +:10664000E074C3F3C900C3F34E335B0103EA0406ED +:10665000014646EA81750139C2F86052F9D2203B01 +:1066600013F1200FF2D1BFF34F8F536943F48033FE +:106670005361BFF34F8FBFF36F8F70BD00ED00E02C +:10668000FEE70000214B2248224A70B5904237D3E2 +:10669000214BC11EDA1C121A22F003028B4238BFB2 +:1066A00000220021FBF77AF91C4A0023C2F884304B +:1066B000BFF34F8FD2F8803043F6E074C3F3C900C4 +:1066C000C3F34E335B0103EA0406014646EA8175D3 +:1066D0000139C2F86C52F9D2203B13F1200FF2D1EC +:1066E000BFF34F8FBFF36F8FBFF34F8FBFF36F8F2A +:1066F0000023C2F85032BFF34F8FBFF36F8F70BDCE +:1067000053F8041B40F8041BC0E700BFC485000811 +:1067100078740020787400207874002000ED00E088 +:10672000054B996B21EA000199631A6E22EA000277 +:106730001A661B6E704700BF0045025870B5D0E95D +:10674000244300224FF0FF359E6804EB42135101B1 +:10675000D3F80009002805DAD3F8000940F080409A +:10676000C3F80009D3F8000B002805DAD3F8000BB2 +:1067700040F08040C3F8000B013263189642C3F822 +:106780000859C3F8085BE0D24FF00113C4F81C3875 +:1067900070BD0000890141F02001016103699B0681 +:1067A000FCD41220FFF7EEB810B50A4C2046FEF7D5 +:1067B0007DFD094BC4F89030084BC4F89430084C68 +:1067C0002046FEF773FD074BC4F89030064BC4F823 +:1067D000943010BD8872002000000840008400083A +:1067E00024730020000004400C84000870B5037876 +:1067F0000546012B58D13F4BD0F89040984254D1D8 +:106800003D4B0E2165209A6B42F000629A631A6E2E +:1068100042F000621A661B6E384BD3F8802042F0BB +:106820000062C3F88020D3F8802022F00062C3F811 +:106830008020D3F88030FEF79FF9314BE360314B75 +:10684000C4F800380023D5F89060C4F8003EC02397 +:1068500023604FF40413A3633369002BFCDA012394 +:106860000C203361FFF78EF83369DB07FCD412206C +:10687000FFF788F83369002BFCDA00262846A6606B +:10688000FFF75CFF6B68C4F81068DB68C4F8146835 +:10689000C4F81C6863BB1C4BA3614FF0FF336361FA +:1068A000A36843F00103A36070BD184B9842C9D19F +:1068B000114B4FF080609A6B42F000729A631A6E2F +:1068C00042F000721A661B6E0C4BD3F8802042F027 +:1068D0000072C3F88020D3F8802022F00072C3F841 +:1068E0008020D3F88030FFF71BFF0E214D20A2E758 +:1068F000074BD1E788720020004502580044025837 +:106900004014004003002002003C30C024730020EB +:10691000083C30C0F8B5D0F89040054600214FF053 +:1069200000662046FFF736FFD5F8941000234FF09D +:1069300001128F684FF0FF30C4F83438C4F81C28B7 +:1069400004EB431201339F42C2F80069C2F8006BA6 +:10695000C2F80809C2F8080BF2D20B68D5F89020EB +:10696000C5F89830636210231361166916F010069B +:10697000FBD11220FFF706F8D4F8003823F4FE63A9 +:10698000C4F80038A36943F4402343F01003A36123 +:106990000923C4F81038C4F814380B4BEB604FF0DF +:1069A000C043C4F8103B094BC4F8003BC4F810695D +:1069B000C4F80039D5F8983003F1100243F480137D +:1069C000C5F89820A362F8BDDC8300084080001061 +:1069D000D0F8902090F88A10D2F8003823F4FE63A3 +:1069E00043EA0113C2F80038704700002DE9F8436C +:1069F00000EB8103D0F890500C468046DA680FFA1D +:106A000081F94801166806F00306731E022B05EB98 +:106A100041134FF0000194BFB604384EC3F8101B69 +:106A20004FF0010104F1100398BF06F1805601FAFE +:106A300003F3916998BF06F5004600293AD0578ABA +:106A400004F15801374349016F50D5F81C180B4326 +:106A50000021C5F81C382B180127C3F81019A740CE +:106A60005369611E9BB3138A928B9B08012A88BFCE +:106A70005343D8F89820981842EA034301F14002A2 +:106A80002146C8F89800284605EB82025360FFF7BC +:106A900081FE08EB8900C3681B8A43EA84534834AB +:106AA0001E4364012E51D5F81C381F43C5F81C78CD +:106AB000BDE8F88305EB4917D7F8001B21F4004126 +:106AC000C7F8001BD5F81C1821EA0303C0E704F13E +:106AD0003F030B4A2846214605EB83035A60FFF724 +:106AE00059FE05EB4910D0F8003923F40043C0F8F3 +:106AF0000039D5F81C3823EA0707D7E700800010D3 +:106B000000040002D0F894201268C0F89820FFF723 +:106B100015BE00005831D0F8903049015B5813F48D +:106B2000004004D013F4001F0CBF02200120704766 +:106B30004831D0F8903049015B5813F4004004D03C +:106B400013F4001F0CBF02200120704700EB8101ED +:106B5000CB68196A0B6813604B685360704700007C +:106B600000EB810330B5DD68AA691368D36019B9F9 +:106B7000402B84BF402313606B8A1468D0F89020A8 +:106B80001C4402EB4110013C09B2B4FBF3F4634333 +:106B9000033323F0030343EAC44343F0C043C0F884 +:106BA000103B2B6803F00303012B0ED1D2F80838F9 +:106BB00002EB411013F4807FD0F8003B14BF43F088 +:106BC000805343F00053C0F8003B02EB4112D2F86F +:106BD000003B43F00443C2F8003B30BD2DE9F041D7 +:106BE000D0F8906005460C4606EB4113D3F8087BBD +:106BF0003A07C3F8087B08D5D6F814381B0704D524 +:106C000000EB8103DB685B689847FA071FD5D6F86D +:106C10001438DB071BD505EB8403D968CCB98B6925 +:106C2000488A5A68B2FBF0F600FB16228AB9186847 +:106C3000DA6890420DD2121AC3E90024302383F39C +:106C4000118821462846FFF78BFF84F31188BDE8A1 +:106C5000F081012303FA04F26B8923EA02036B81BA +:106C6000CB68002BF3D021462846BDE8F0411847F9 +:106C700000EB81034A0170B5DD68D0F890306C6993 +:106C80002668E66056BB1A444FF40020C2F810098B +:106C90002A6802F00302012A0AB20ED1D3F80808CA +:106CA00003EB421410F4807FD4F8000914BF40F0C5 +:106CB000805040F00050C4F8000903EB4212D2F8B3 +:106CC000000940F00440C2F800090122D3F834085A +:106CD00002FA01F10143C3F8341870BD19B9402E0E +:106CE00084BF4020206020681A442E8A8419013C09 +:106CF000B4FBF6F440EAC44040F00050C6E70000A0 +:106D00002DE9F843D0F8906005460C464F0106EB9C +:106D10004113D3F8088918F0010FC3F808891CD073 +:106D2000D6F81038DB0718D500EB8103D3F80CC078 +:106D3000DCF81430D3F800E0DA68964530D2A2EBE4 +:106D40000E024FF000091A60C3F80490302383F359 +:106D50001188FFF78DFF89F3118818F0800F1DD07F +:106D6000D6F834380126A640334217D005EB840309 +:106D70000134D5F89050D3F80CC0E4B22F44DCF8BD +:106D8000142005EB0434D2F800E05168714514D3A7 +:106D9000D5F8343823EA0606C5F83468BDE8F88328 +:106DA000012303FA01F2038923EA02030381DCF8D9 +:106DB0000830002BD1D09847CFE7AEEB0103BCF8E9 +:106DC0001000834228BF0346D7F8180980B2B3EBFE +:106DD000800FE3D89068A0F1040959F8048FC4F833 +:106DE0000080A0EB09089844B8F1040FF5D81844C6 +:106DF0000B4490605360C8E72DE9F84FD0F89050ED +:106E000004466E69AB691E4016F480586E6103D06B +:106E1000BDE8F84FFEF7BABA002E12DAD5F8003EF8 +:106E20009B0705D0D5F8003E23F00303C5F8003ECC +:106E3000D5F80438204623F00103C5F80438FEF7DE +:106E4000D3FA370505D52046FFF778FC2046FEF734 +:106E5000B9FAB0040CD5D5F8083813F0060FEB6872 +:106E600023F470530CBF43F4105343F4A053EB606E +:106E700031071BD56368DB681BB9AB6923F00803D6 +:106E8000AB612378052B0CD1D5F8003E9A0705D0CD +:106E9000D5F8003E23F00303C5F8003E2046FEF778 +:106EA000A3FA6368DB680BB120469847F30200F150 +:106EB000BA80B70226D5D4F8909000274FF0010A87 +:106EC00009EB4712D2F8003B03F44023B3F5802FBF +:106ED00011D1D2F8003B002B0DDA62890AFA07F3D0 +:106EE00022EA0303638104EB8703DB68DB6813B1E9 +:106EF0003946204698470137D4F89430FFB29B6852 +:106F00009F42DDD9F00619D5D4F89000026AC2F389 +:106F10000A1702F00F0302F4F012B2F5802F00F00E +:106F2000CA80B2F5402F09D104EB8303002200F59B +:106F30008050DB681B6A974240F0B0803003D5F880 +:106F4000185835D5E90303D500212046FFF746FE42 +:106F5000AA0303D501212046FFF740FE6B0303D5AA +:106F600002212046FFF73AFE2F0303D503212046D6 +:106F7000FFF734FEE80203D504212046FFF72EFE7A +:106F8000A90203D505212046FFF728FE6A0203D592 +:106F900006212046FFF722FE2B0203D507212046BB +:106FA000FFF71CFEEF0103D508212046FFF716FE70 +:106FB000700340F1A780E90703D500212046FFF7C1 +:106FC0009FFEAA0703D501212046FFF799FE6B0714 +:106FD00003D502212046FFF793FE2F0703D5032197 +:106FE0002046FFF78DFEEE0603D504212046FFF76D +:106FF00087FEA80603D505212046FFF781FE690616 +:1070000003D506212046FFF77BFE2A0603D507217C +:107010002046FFF775FEEB0574D520460821BDE834 +:10702000F84FFFF76DBED4F890904FF0000B4FF083 +:10703000010AD4F894305FFA8BF79B689F423FF6C1 +:1070400038AF09EB4713D3F8002902F44022B2F518 +:10705000802F20D1D3F80029002A1CDAD3F8002988 +:1070600042F09042C3F80029D3F80029002AFBDB44 +:107070003946D4F89000FFF78DFB22890AFA07F30E +:1070800022EA0303238104EB8703DB689B6813B1C7 +:107090003946204698470BF1010BCAE7910701D109 +:1070A000D0F80080072A02F101029CBF03F8018B8F +:1070B0004FEA18283FE704EB830300F58050DA68B5 +:1070C000D2F818C0DCF80820DCE9001CA1EB0C0C9D +:1070D00000218F4208D1DB689B699A683A449A6024 +:1070E0005A683A445A6029E711F0030F01D1D0F8E9 +:1070F00000808C4501F1010184BF02F8018B4FEA49 +:107100001828E6E7BDE8F88F08B50348FFF774FED6 +:10711000BDE80840FDF7DAB98872002008B50348D9 +:10712000FFF76AFEBDE80840FDF7D0B924730020E0 +:10713000D0F8903003EB4111D1F8003B43F4001339 +:10714000C1F8003B70470000D0F8903003EB4111CC +:10715000D1F8003943F40013C1F80039704700003A +:10716000D0F8903003EB4111D1F8003B23F4001329 +:10717000C1F8003B70470000D0F8903003EB41119C +:10718000D1F8003923F40013C1F80039704700002A +:1071900030B50433039C0172002104FB0325C16058 +:1071A000C0E90653049B0363059BC0E90000C0E9E6 +:1071B0000422C0E90842C0E90A11436330BD00005F +:1071C0000022416AC260C0E90411C0E90A226FF0DE +:1071D0000101FEF747BC0000D0E90432934201D11F +:1071E000C2680AB9181D704700207047036919600A +:1071F0000021C2680132C260C269134482699342AD +:10720000036124BF436A0361FEF720BC38B504461E +:107210000D46E3683BB162690020131D1268A3624A +:107220001344E36207E0237A33B929462046FEF788 +:10723000FDFB0028EDDA38BD6FF00100FBE7000030 +:10724000C368C269013BC3604369134482699342C6 +:10725000436124BF436A436100238362036B03B12C +:107260001847704770B53023044683F31188866A47 +:107270003EB9FFF7CBFF054618B186F311882846C3 +:1072800070BDA36AE26A13F8015B9342A36202D362 +:107290002046FFF7D5FF002383F31188EFE70000B6 +:1072A0002DE9F84F04460E46174698464FF0300930 +:1072B00089F311880025AA46D4F828B0BBF1000F45 +:1072C00009D141462046FFF7A1FF20B18BF3118879 +:1072D0002846BDE8F88FD4E90A12A7EB050B521A2D +:1072E000934528BF9346BBF1400F1BD9334601F1AC +:1072F000400251F8040B914243F8040BF9D1A36A00 +:10730000403640354033A362D4E90A239A4202D37F +:107310002046FFF795FF8AF31188BD42D8D289F342 +:107320001188C9E730465A46FAF712FBA36A5E4451 +:107330005D445B44A362E7E710B5029C043301722D +:1073400003FB0421C460C0E906130023C0E90A332B +:10735000039B0363049BC0E90000C0E90422C0E969 +:107360000842436310BD0000026A6FF00101C26071 +:10737000426AC0E904220022C0E90A22FEF772BB79 +:10738000D0E904239A4201D1C26822B9184650F8C4 +:10739000043B0B60704700231846FAE7C3680021DE +:1073A000C2690133C36043691344826993424361F4 +:1073B00024BF436A4361FEF749BB000038B5044669 +:1073C0000D46E3683BB1236900201A1DA262E26901 +:1073D0001344E36207E0237A33B929462046FEF7D7 +:1073E00025FB0028EDDA38BD6FF00100FBE7000057 +:1073F00003691960C268013AC260C26913448269B4 +:107400009342036124BF436A036100238362036BD9 +:1074100003B118477047000070B530230D4604468D +:10742000114683F31188866A2EB9FFF7C7FF10B1A2 +:1074300086F3118870BDA36A1D70A36AE26A0133E6 +:107440009342A36204D3E16920460439FFF7D0FFD9 +:10745000002080F31188EDE72DE9F84F04460D4632 +:10746000904699464FF0300A8AF311880026B346B9 +:10747000A76A4FB949462046FFF7A0FF20B187F31E +:1074800011883046BDE8F88FD4E90A073A1AA8EB0C +:107490000607974228BF1746402F1BD905F1400326 +:1074A00055F8042B9D4240F8042BF9D1A36A4036CD +:1074B0004033A362D4E90A239A4204D3E169204607 +:1074C0000439FFF795FF8BF311884645D9D28AF32B +:1074D0001188CDE729463A46FAF73AFAA36A3D44BD +:1074E0003E443B44A362E5E7D0E904239A4217D126 +:1074F000C3689BB1836A8BB1043B9B1A0ED01360A7 +:10750000C368013BC360C3691A4483699A4202613C +:1075100024BF436A03610023836201231846704736 +:107520000023FBE700F05CBA014B586A704700BFCC +:10753000000C0040034B002258631A610222DA60FB +:10754000704700BF000C0040014B0022DA6070471A +:10755000000C0040014B5863704700BF000C004016 +:10756000024B034A1A60034A5A607047D8730020DE +:107570007874002000000220074B494210B55C6877 +:10758000201A08401968821A8A4203D3A24201D8FD +:107590005A6010BD0020FCE7D873002008B53023E6 +:1075A00083F31188FFF7E8FF002383F3118808BDF8 +:1075B00004480121044B03600023C0E901330C306F +:1075C00000F016B9E07300209D750008CB1D083A45 +:1075D00023F00703591A521A012110B4D2080024CB +:1075E000C0E9004384600C301C605A605DF8044BB5 +:1075F00000F0FEB82DE9F84F364ECD1D0F4600289D +:1076000018BF0646082A4FEAD50538BF082206F1FA +:107610000C08341D9146404600F006F909F10701B7 +:10762000C9F1000E224624686CB9404600F006F904 +:107630003368CBB308224946E8009847044698B31C +:1076400040E9026730E004EB010CD4F804A00CEA36 +:107650000E0C0AF10100ACF1080304EBC0009842E3 +:10766000E0D9A0EB0C0CB5EBEC0F4FEAEC0BD9D842 +:107670009C421CD204F10802AB45A3EB02024FEA84 +:10768000E202626009D9691CED43206803EBC10284 +:107690005D44556043F8310022601C465F604046FF +:1076A00044F8086B00F0CAF82046BDE8F88FAA45F8 +:1076B000216802D111602346EFE7013504EBC503D1 +:1076C00044F8351003F10801401AC01058601360E7 +:1076D000F1E700BFE0730020F8B550F8043C044621 +:1076E00050F8085CA0F1080607332F1D0C35DB08A5 +:1076F00040F8043C284600F097F83B469F421A6841 +:1077000001D0B34228D20AB1964225D244F8082CBF +:1077100054F8042C1E60013254F8081C06EBC20019 +:10772000814206D14868024444F8042C0A6844F8AF +:10773000082C5868411C03EBC1018E4207D154F854 +:10774000042C013202445A6054F8082C1A6028466E +:10775000BDE8F84000F072B81346CFE7FEE700003E +:1077600070B51B4B0025044686B058600E468562F6 +:107770000163FCF783FE04F11003A560E562C4E930 +:1077800004334FF0FF33C4E90044C4E90635FFF782 +:10779000CBFE2B46024604F134012046C4E90823FF +:1077A00080230C4A2565FEF7F7F801230A4AE060BA +:1077B00000920375684672680192B268CDE90223AF +:1077C000064BCDE90435FEF70FF906B070BD00BFDA +:1077D00098560020188400081D8400085D77000872 +:1077E000024AD36A1843D062704700BF3054002069 +:1077F000C0E90000816070478368013B002B10B531 +:1078000083600CDA074BDC684368A061206063602A +:107810001C6044600520FEF721F8A06910BD00201F +:10782000FCE700BF3054002008B5302383F31188F3 +:10783000FFF7E2FF002383F3118808BD08B530236A +:1078400083F3118883680133002B836007DC0368AE +:1078500000211A68026050601846FEF72BF80023DA +:1078600083F3118808BD00004B6843608B68836018 +:10787000CB68C3600B6943614B6903628B694362E8 +:107880000B6803607047000008B53C4B40F2FF7185 +:107890003B48D3F888200A43C3F88820D3F88820CF +:1078A00022F4FF6222F00702C3F88820D3F8883060 +:1078B000344B1A6C0A431A649A6E0A439A66324A27 +:1078C0009B6E1146FFF7D0FF00F5806002F11C01AE +:1078D000FFF7CAFF00F5806002F13801FFF7C4FF2F +:1078E00000F5806002F15401FFF7BEFF00F58060F3 +:1078F00002F17001FFF7B8FF00F5806002F18C0122 +:10790000FFF7B2FF00F5806002F1A801FFF7ACFFBE +:1079100000F5806002F1C401FFF7A6FF00F580606A +:1079200002F1E001FFF7A0FF00F5806002F1FC0129 +:10793000FFF79AFF02F58C7100F58060FFF794FF66 +:1079400000F010F9114BD3F8902242F00102C3F875 +:107950009022D3F8942242F00102C3F89422052227 +:10796000C3F898204FF06052C3F89C20084AC3F82F +:10797000A020BDE80840FEF7E1BD00BF004402586A +:1079800000000258004502582484000800ED00E081 +:107990001F00080308B500F0C3FAFDF7C7FF0D4B41 +:1079A000DA6B42F04002DA635A6E22F040025A6605 +:1079B0005B6E094B1A6842F008021A601A6842F0BE +:1079C00004021A60FEF702FEFEF7BEFCBDE80840A6 +:1079D000FEF744BA004502580018024870470000FC +:1079E0000E4B9A6C42F008029A641A6F42F0080239 +:1079F0001A670B4A1B6FD36B43F00803D363C7228C +:107A0000084B9A624FF0FF32DA6200229A615A63A1 +:107A1000DA605A6001225A611A60704700450258C4 +:107A20000010005C000C0040094A08B51169D368D9 +:107A30000B40D9B29B076FEA0101116107D53023D2 +:107A400083F31188FDF79CFF002383F3118808BDA1 +:107A5000000C0040044BDA6B0243DA635A6E1043A9 +:107A600058665B6E704700BF0045025808B53C4B36 +:107A70004FF0FF31D3F8802062F00042C3F880203D +:107A8000D3F8802002F00042C3F88020D3F8802091 +:107A9000D3F88420C3F88410D3F884200022C3F8DC +:107AA0008420D3F88400D86F40F0FF4040F4FF00FA +:107AB00040F4DF4040F07F00D867D86F20F0FF40EF +:107AC00020F4FF0020F4DF4020F07F00D867D86F5B +:107AD000D3F888006FEA40506FEA5050C3F888002E +:107AE000D3F88800C0F30A00C3F88800D3F88800F0 +:107AF000D3F89000C3F89010D3F89000C3F890200A +:107B0000D3F89000D3F89400C3F89410D3F89400FD +:107B1000C3F89420D3F89400D3F89800C3F89810D1 +:107B2000D3F89800C3F89820D3F89800D3F88C00C5 +:107B3000C3F88C10D3F88C00C3F88C20D3F88C00D9 +:107B4000D3F89C00C3F89C10D3F89C10C3F89C2079 +:107B5000D3F89C30FCF73CFEBDE8084000F0B4B917 +:107B60000044025808B50122504BC3F80821504B7D +:107B70005A6D42F002025A65DA6F42F00202DA6789 +:107B80000422DB6F4B4BDA605A689104FCD54A4AF9 +:107B90001A6001229A60494ADA6000221A614FF4A1 +:107BA00040429A61434B9A699204FCD51A6842F4A8 +:107BB00080721A60424B1A6F12F4407F04D04FF467 +:107BC00080321A6700221A671A6842F001021A60AE +:107BD0003B4B1A685007FCD500221A611A6912F053 +:107BE0003802FBD1012119604FF0804159605A677A +:107BF000344ADA62344A1A611A6842F480321A60EE +:107C00002F4B1A689103FCD51A6842F480521A600F +:107C10001A689204FCD52D4A2D499A6200225A63B3 +:107C2000196301F57C01DA6301F5E77199635A6420 +:107C3000284A1A64284ADA621A6842F0A8521A607E +:107C40001F4B1A6802F02852B2F1285FF9D148227E +:107C50009A614FF48862DA6140221A621F4ADA643C +:107C60001F4A1A651F4A5A651F4A9A6532231F4ADE +:107C70001360136803F00F03022BFAD1104A136943 +:107C800043F003031361136903F03803182BFAD18F +:107C90004FF00050FFF7DEFE4FF08040FFF7DAFEB6 +:107CA0004FF00040BDE80840FFF7D4BE008000510F +:107CB000004502580048025800C000F004000001CE +:107CC000004402580000FF01008890083220600044 +:107CD00063020901470E0508DD0BBF0120000020EB +:107CE000000001100910E000000101100020005206 +:107CF0004FF0B04208B5D2F8883003F00103C2F863 +:107D0000883023B1044A13680BB150689847BDE826 +:107D10000840FCF7DBBB00BFF87300204FF0B04217 +:107D200008B5D2F8883003F00203C2F8883023B1D6 +:107D3000044A93680BB1D0689847BDE80840FCF747 +:107D4000C5BB00BFF87300204FF0B04208B5D2F8B1 +:107D5000883003F00403C2F8883023B1044A136961 +:107D60000BB150699847BDE80840FCF7AFBB00BFB6 +:107D7000F87300204FF0B04208B5D2F8883003F015 +:107D80000803C2F8883023B1044A93690BB1D06963 +:107D90009847BDE80840FCF799BB00BFF873002086 +:107DA0004FF0B04208B5D2F8883003F01003C2F8A3 +:107DB000883023B1044A136A0BB1506A9847BDE872 +:107DC0000840FCF783BB00BFF87300204FF0B043BE +:107DD00010B5D3F8884004F47872C3F88820A3065D +:107DE00004D5124A936A0BB1D06A9847600604D54D +:107DF0000E4A136B0BB1506B9847210604D50B4A02 +:107E0000936B0BB1D06B9847E20504D5074A136C0E +:107E10000BB1506C9847A30504D5044A936C0BB181 +:107E2000D06C9847BDE81040FCF750BBF8730020B9 +:107E30004FF0B04310B5D3F8884004F47C42C3F847 +:107E40008820620504D5164A136D0BB1506D984712 +:107E5000230504D5124A936D0BB1D06D9847E00409 +:107E600004D50F4A136E0BB1506E9847A10404D588 +:107E70000B4A936E0BB1D06E9847620404D5084A42 +:107E8000136F0BB1506F9847230404D5044A936FC6 +:107E90000BB1D06F9847BDE81040FCF717BB00BF8F +:107EA000F873002008B50348FCF7E0FDBDE8084082 +:107EB000FCF70CBBC44F002008B5FFF7B5FDBDE8CB +:107EC0000840FCF703BB0000062108B50846FCF794 +:107ED00053FE06210720FCF74FFE06210820FCF781 +:107EE0004BFE06210920FCF747FE06210A20FCF77D +:107EF00043FE06211720FCF73FFE06212820FCF751 +:107F00003BFE09217A20FCF737FE07213220FCF7DF +:107F100033FE0C215220BDE80840FCF72DBE0000C6 +:107F200008B5FFF7A3FD00F00DF8FCF7E3FFFDF740 +:107F3000BBF9FDF78DF8FFF751FDBDE80840FFF7ED +:107F4000F1BA00000023054A19460133102BC2E99B +:107F5000001102F10802F8D1704700BFF873002049 +:107F60000B460146184600F001B8000010B5054C5C +:107F700013462CB10A4601460220AFF3008010BD23 +:107F80002046FCE70000000010B501390244904291 +:107F900001D1002005E0037811F8014FA34201D080 +:107FA000181B10BD0130F2E72DE9F041A3B1C91A49 +:107FB00017780144044603F1FF3C8C42204601D966 +:107FC000002009E00578BD4204F10104F5D10CEB75 +:107FD0000405D618A54201D1BDE8F08115F8018D40 +:107FE00016F801EDF045F5D0E7E70000034611F87B +:107FF000012B03F8012B002AF9D170476F72672E0D +:108000006172647570696C6F742E437562654E6F32 +:108010006465000053544D333248373F3F3F0053AF +:10802000544D3332483733782F3732780053544D1C +:108030003332483734332F3735332F37353000005C +:1080400001105A0003105900012058000320560067 +:1080500040A2E4F1646891060041A3E5F2656992EB +:108060000700000043414E464449666163653A207B +:108070004D6573736167652052414D204F7665727F +:10808000666C6F77210000004261642043414E49D5 +:108090006661636520696E6465782E0000000000EB +:1080A00000000000492B0008AD2300089D320008A5 +:1080B0001D240008292400086D280008CD2500088B +:1080C000E5230008E9230008C1230008A9230008CC +:1080D00029280008CD23000831340008D5330008D2 +:1080E000D9230008FD27000801040E05054B0202F4 +:1080F0000E05054B04010E05054B05010B04044B51 +:108100000801060303460000100002400800024078 +:108110000008024000000B00280002400800024056 +:108120000408024006010C00400002400800024022 +:108130000808024010020D005800024008000240EA +:108140000C08024016030E00700002400C000240B2 +:108150001008024000040F00880002400C0002409A +:108160001408024006051000A00002400C00024066 +:108170001808024010061100B80002400C0002402E +:108180001C08024016072F00100402400804024099 +:108190002008024000083800280402400804024079 +:1081A0002408024006093900400402400804024045 +:1081B00028080240100A3A0058040240080402400D +:1081C0002C080240160B3B00700402400C040240D5 +:1081D00030080240000C3C00880402400C040240BD +:1081E00034080240060D4400A00402400C04024082 +:1081F00038080240100E4500B80402400C0402404A +:108200003C080240160F46000096000000000000E7 +:10821000000000000000000000000000000000005E +:1082200000000000B54E0008A14E0008DD4E000819 +:10823000C94E0008D54E0008C14E0008AD4E0008DA +:10824000994E0008E94E000800000000CD4F0008DC +:10825000B94F0008F54F0008E14F0008ED4F000846 +:10826000D94F0008C54F0008B14F00080150000861 +:10827000000000000100000000000000633000006A +:108280007C82000888540020985600204172647552 +:1082900050696C6F740025424F415244252D424C69 +:1082A000002553455249414C2500000002000000C2 +:1082B00000000000ED5100085D5200084000400041 +:1082C000486F0020586F00200200000000000000EE +:1082D0000300000000000000A5520008000000009C +:1082E00010000000686F0020000000000100000086 +:1082F000000000008872002001010200F95D000802 +:10830000095D0008A55D0008895D000843000000C4 +:108310001483000809024300020100C0320904006E +:1083200000010202010005240010010524010001E2 +:10833000042402020524060001070582030800FF49 +:1083400009040100020A00000007050102400000C4 +:108350000705810240000000120000006083000851 +:1083600012011001020000400912415700020102EF +:10837000030100000403090425424F415244250033 +:10838000303132333435363738394142434445464B +:10839000000000000001002000FF010002000000BA +:1083A000000000300000040008000000000000246D +:1083B00000000800040000000004000000FC0000B1 +:1083C00002000000000004300080000008000000EF +:1083D0000000003800000100010000000000000063 +:1083E00001540008B95600086557000840004000D5 +:1083F000C0730020C073002001000000D073002073 +:1084000080000000400100000800000000010000A2 +:1084100000100000080000006D61696E0069646C66 +:10842000650000000000802A00000000AAAAAAAA95 +:1084300000000024FFFF00000000000000A00A0070 +:108440000000000000000000AAAAAAAA0000000084 +:10845000FFFF00000000000000000000000000001E +:1084600000000000AAAAAAAA00000000FFFF000066 +:1084700000000000000000000A00000000000000F2 +:10848000AAAAAAAA00000000FFFF000099000000AD +:10849000000000000080020000000000AAAAAAAAB2 +:1084A00000400100FFFF0000000000700700000016 +:1084B0000000000000000000AAAAAAAA0000000014 +:1084C000FFFF0000000000000000000005000000A9 +:1084D00000000000A5AAAAAA00000000FCFF0000FE +:1084E000000000000000000000000000000000008C +:1084F000AAAAAAAA00000000FFFF000000000000D6 +:10850000000000000000000000000000AAAAAAAAC3 +:1085100000000000FFFF000000000000000000005D +:108520000000000000000000AAAAAAAA00000000A3 +:10853000FFFF00000000000000000000000000003D +:1085400000000000AAAAAAAA00000000FFFF000085 +:1085500000000000000000003704000000000000E0 +:108560000000180000000000FE2A0100D2040000F4 +:10857000FF000000A0560020C44F002000000000B3 +:1085800014800008830400001F80000850040000CD +:108590002D800008009600000000080096000000F2 +:1085A00000080000040000007483000800000000C0 +:1085B00000000000000000000000000000000000BB +:0485C00000000000B7 :00000001FF diff --git a/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin b/Tools/bootloaders/CubeRedPrimary-PPPGW_bl.bin index 449a2062ae4dffe3cedb97402f0b822460a60429..af108e9c444f5e1083c7bc60e29cebe2c346f8f4 100755 GIT binary patch delta 15630 zcmb7rdt6l2`uARQfz5po5fG3W24oOX5D~m37v0>v{z}cv1W6rK61?PH@ET|qx~kF4 z+c8rzlL-kYBlKveQ)xkJX_jebBbB-_WzR6T_qzuC)psilw*8O>& zwdS>2j}r$y5;;#!-7e$!(hD3P3ykXy#~}O@>3>J<_QZrSsab?C0=5Ar;5MLfaeN-I z6gU7}03HDvj<^|I{gUI!d5*t}Fc@JVH4^Rij8HE}b{E0Y?Ki^%#&uJ(Dq}~J?E`~D zRv_sBZ~?Fav4rqMfvhl}arj&T93t-MiXmN`P_OrnS}e~|_Qux^dR!hCA^Vv138w`(j_2=kH#mZCq@Avz z59GO?yu)b@6kBPgqS

r>D?EjG>;&>0b9b`wE=8hd7JQSI$U0@-*T54)dz}7@?|x zAFF8RIbX5Lrf46GaHCBvDDo9~O?OloJ;fRHkuoRXM?0qt&Y$pbWqD9;pm?4ZczmY( z&Duk>*N1qHBLSb=IPGzF_Az9itY6IUQjkN`&o7&7pp*Rekn{AuUn03pBmJj^>#cr| zCan>hxaQ-3a+Q1Moztw_BHUZhms4M%+x-v8cq>g0sPSsH?9cM}(MP;STLY5GS5&SV zPTrxTR4I{fS~gp_{b$T6%RLhmS4c`qnP*+o9r0CJuD|#)eN`1jj?m+(Kgkk$FfffM z=(WJeIDQr36WhcIuhuCAUx7RBCw4kHT|ujMtt=tD_0|@W5ZdY^o}f`ZW{@eCk8s)QUzceiv1RKBAXRCin=0!7aiu2>*xM zMWc45_wm&6Ttd%gxmKoKT<#-2r29gW33?zTjtr#MklkbqeLZwt${ed&P&KI4r z`Iroii6&sw!!MzaeD#hj=7QC^Hkzm*v?a(%>S ztwg-;^sKotkBHx+^nQfjg5x#w&^%?0TF;BAHszaXdF(66HYBgtk%8mA3&r7r_6EIN#us3@(lfYETG7d|>w%{aqu# z-_zw?pe`H{?Uk3&VNr3fsl<5>&w>%ro_U3Zk5h^qvN}~0=ihuaoa4*D%oxe>%PHwI zj_B!xK4HW~OZu$xO0X%h9jU~)`n!GPByb}L_X5X&o@i4ICF(@2#ilk5&C_8I`_p#B z7?{*U9BI=CG9gKDNh+5PJ^MMGqz*=p%vDcDpEs#Pf?smw3ryya3OztX|_e<^KK zM-4A^+%)UJTMv{0>w(vRI^bjAGhi`V+|tGomo&!}t4C{v>v}J7BF)wmk!kdhX49D0 ztm?`ny|!vYmhTlVR$WEXRpMr=wn{mg3~zW;IZ#{q@M2k$N?dJC(IYLT;So0~rSSH} zJLX<dhj>>X8G?z7%LDI~Q=X;Gdp2&(7bj_)PPIx{%KuoD`*J??~?~Y_7 z_=`c<3H-%h9HDtE^rZ>08kv`ij*sovE2;@xR&nZ#O*jKyy!uWjwRCphSg(Fgg;0qWd_`&B`3ZfUXkAob3m4-(9!DP5%Y9c$)xj*~ zRh?cvnhXvQ6I~r<4(YdOd|X<^L8mrS7OmFkgwuU}#kZWrk@Dzh#C*j!oCon8>;A5B zV%Ex4(K>gm8Zniek4|^T)*}{(ScW^c3b7uD<+@`_5bG&dM^ALeN)Zc{XGE8|V{;Hw z>p)uPj?P3>gV;%T>}hARzz-QN@Xyhc=SzWKHxHA3BQh%^K({-g6vuf5+ncj)Uxc z+(2LPCcUkT#o6W)A4bm5*!X0eTvOxY0$+1v3$1^v6Q^2yT{yG75rj+#eVc!{1}<1oksWTA1vAyM_e-T(JWIH6No9{EB;E0`(=}J z^l-mKs3Dj8X~-2S^@~GFRDy=o)69fO@;05B5KmsE)d_Lv2xCGJNu{4A*MIuZ z<v_m0qx|CM$*p&asP0kyD+*Ep?|8c+NGYJ2K zD-!yPj9*7*Bx-#AWtZ2@uqbR?^Kx39IEu`tpC?9Jd!+1(*~vZecYKHp%m`6sMWk! zN0$wX4U(glzRO&apX;KTZ^+ei;xF|0pzvwmc5=I;1yW0DWT5@r;@$)~PV3n~1oEy- zO(-vZZy`H5@l0n|W6K(P388{2+7GiR0`ecWBw^cnzf-0ytkem`WiIK4ixc0a+LTNp zr?XSy6Sg>2(aFO85>N4BCrQd{@!XvuC@3fDJ9(|LMjoAsIiNVo@|RLmik9TjA5*kx zD{xH~0u>JC4L$`^)s^;NXfMtdECzPa4O+g=s+I#RgB|^*Udnmk@ttqD7+~R39WN zh_*F9njCRTyIffvgM*S*9kVEsQuG%r-br5KUAqz^o*e1d?$0@;DXs|}u0^$xvLi0( zMVqqSTXxLi!I9djmKe?@opA)$LCwV17tM(kQ2vy{fjTZ`?RdZTp8P3PRz7Ow78I~TC9HCkAhCs#YA zH>@6y-kG9EQw`zz&uTf;uJ96sxnrM4j?MX{FwLR};B=h$Q6;C%kM^rgbxHqp>~Hsx zuNOuo#9wK$3|6z&y_uCE)>e`z)((HPqNlCNG9+mOQukJJ(eKjc)ZmJ-_EGwD%n{BW zpi^8`MSIn<*g~k}Ui6qHDd|F+cS?$$rC)?zJP~=H+f_PGVM(hOQ|h&EBNE6Gz8C z*x19bHgvS2JxR`4#*IkVyQF^38dJ2;&)pN=*6+G|N7?c;7=LenTHwWHot$=f;cU8V zNO(nL-cRQ5EqoHM&K6bjFW8qjrE`O@+}IQSJgHMI=!_E{9x0dCxTIk=`R*?*ToR|< zih<9y#JKyt;^C0v(SmQ@DYN3yJ5L=Q!L4O~%#-9~F53EUt z2Dg;HINVMK(ZwV3ly{K$1wAt&Qfs&QL7n=vGsDPfmFvc=%U-Nle7cPrLbPYsl{GOs zUrI)f!Qf-;E#qWci^c6^r4I{r>8Dl)ppw zJ+X}3pdq7DaQ+pH(j>F;`%x|fDopYSj$aR>vl3Wh`SR#om$ZlO z88tBcrsaw$C_m#tQ(#Y|t?g9dyE(82zL!(;sK@~&ovr4LS>{%?e)hW9b-d9feeC44 z+Co@z>sXB+gZm!*#nHN)_&F6 z>e#}d(b{!CVNNj0bQGUW9T}x0m(I@&3#zpiS7(n=ev>auc(}HlErb2kkXhul9CVES zRZ6m^ldtKFtW=+9m{95N0eO$^$$C=OGMhfg>L2%mMI#V3Gmm-k{pQms_%pyx9-S!w zz3^JOKZN<5j>(P<`Os3lHTxmAxOf8-ozXr7IJz!7XygHlr&!)uymhxS@bayNtBlht z5=@?GOm-lT@;fX)FMP6s41aQ2@mB4B;n12LL{`w-*-v_Oaivd;Uh8pgDd8dIKS!sN zkEm_*45)9@U`S;aa6F?5rN_pEkZStrnBjr*U7ULMrn_dAo?Art1vF5IB2Us}VU&iY zRUwVFDc6{xXQQ(T%D23`)i%0a(0T^CYe<5!Re?s@%jLOF=}XX7cGEsAqT_S=_%$G@raLKuuE-ghwgV|I z7tUT*=4Ls17CT*ZCJcLriFkm?dZ)6$BR^E%L$4YgTF7_z^YgSVClX4tXKtjDiBee~ zpIc4>_Bs+xF(~>9i9t~Vt<6getaKDF{N30SL+4!-f>cbjW_{GE&-#ligSS~U@Xuw z8yh6TyT$dNjF-uX4?Qz6D42Baw)9kc_fxhG!d`MNa}%V-ZaC3JmeICJ>w<<@uUQtT z`np>@|hG__})n)pZt>))4-=@ zlO($AsW=ir_dOL!{AkltA%UksVTmDJC_*N4IlcWsJ(n?dONn|ojeCBoHP0v2FJ&YB7fTFUwgbxJt z5JH1+DlMIUlZ>Vlp1n-2(%2ccUW{@(a#n+)5@3|a=hhE-E}F1KJ~PVQJPlnlGYrR+ zVdfZ;NPnE!3K!$?!h+y?)&zaO>hS6}v$nT*<=@Z*K_+xUQDg<;ZX>+DuClFpbDNe0kWb1nxmN=*sjp8{1T!l|@qZWwvLe$`wTfs<}k z$qIMx%%j$lC|Okr?LF`PUY?F({mxY+J+zsq*=l_o<-RDP*XQ*icd29E1o9~zH$TLS zC5u1+Eu9}3@{YZ)sbBtKO+v0++Harm+ZLrp*}C9x+~Yur@{+0GR{V?yr3h$Q?hUr`I2TXj3p=O+=ZzG2l>Kj zL`J2BMX&>>m6ZnYou0cx@2UEg>92;_BuX!r#j)NhTRf!Ry6@L8!4A*SduArhYp8GS z0>XcVkV6;(qydwGW5DmgvQqj^d4JY%<>Sb7s#!D@R`7~Ni6oRBUNn>3p`MGA;~6t6 zh`mb*p9L%f65FH+ega$b)6vxN$9kD;CYsqjJ>cf}D z2A*;yR3{k2L79`;2YL0heCY(Tm7ZA|l*nqZfa|yyaG(N*fF{5USlkK%Q;F^;_dvP% zl)RW7&Pu2jb}3S9#2MeYMd8RFL1(@=JB;P`M}Al7-pKv5C=9s{`s0f;l`MB6&0H3Q zj+?wJr)yLf(tj-5!nT>^T?thS>B{B3gEZK_*y+0!Jj|IdgGXrnVVL8=B@Vq_D_pkt z)_G`T)fX&WjZzGtVJquVM0VRN!f^RrYgClQJ-`zGF92*GB^+)7>hhnW~Te-?B!5Hh3%rg)ckl+ z4hDT$w{n%yF_-v*KF6*uCFwRgVRd46AFNv)Ow`n{`cNzrdO>#?U$wswEGWfSJCjVR z{7*Eh+@?Ea88$Xq)}(pVfU2>K?p-s49H5uiMD;GW$;E}vK|;Ks9?b|{(%xo9^stQj zuN?-HI&WmO=D`~tnZc41&s=Sf(Hiq-}BEt*nD*g#7wR*~(rts*?E zq_e?1Z;O1_maMU@j7r&>kzb{;Ni%3<V5cDP`!f;&7=|Y?3!k?9a(Vv+YiUA(wX2$JCIel@% z`?7y8rF}PkLq4O{jq!f(z=M}$><>fUD($2LHMi&dF=;l{u?Zj(=R5nGM&aDfFCPWrci0D*MxZJ2$s-WkYELw!Bi1i@7-Adg*ITdl zdfb?wnFZ3#xBp7|$;-KHTiP}f&ZIHhv>tCG>-=K+!nTPxW}3H64;DM);h^r6UUBJ+ zvH2frV!`n#I`Eb0B#Ul+C84LvwgLJED`o-M;Pziazj$RVGq_$&B{%7~SJS+i7GJmo zOKu5$<<-3y@Wh(9A(=3zwS`My$y=KG32o*#vy`n$w5Yn=19c4Q9In?EjwrluK7!V> z!smdFC3H*86cSQ@v*tJZHSa|3;YwV+R?)pX zKPcG!alA>1?i>@S%(Y4%J7A+hEUvi@499u`(NC923KgEv~ z$Ur59KpQpfe@Vk8lW9M$cp9qfF0>I+BFJ;)JBYZc)64C4y-kY_WRf@O!2^jNWhnLf zviffiRFbgMmf`yF<#JJ!s}htgSrF{g5KL+>w*RIb_%9d}XMf&@p$paYg z2=L^=%ezIb<69Iuj}}F4M#r3FdA>y&4qKVomHk0ewv4{;PVay?=m$*C8knidwMaO5 z-WjNR)2W2Rkue($!b!{Nx9^Q5BIP578~^)W5WNAfTG1qEOgD($_v}fs`h{YIedFhyLxFm%nI=< z)Nmd76J1?>`7evE@LRJCH8R`f15Fxg9N{Dy*-rRj?AZ|t!LwDiQzpLR@Dhi(LcsHk zd6Z6hm2K{)uoNv)EZufwXxt))QuwzqB9~~m-xVsCv;dcG3ULi;+lJa)kdVcf(z{18 zRdXD3yT_;uO|M)|pQud=8Vu5VApH=eIF~qum_XOnhJ;7C?+LzdQHZ@kaS0S}IlDyf zLF;R0$2*)S+X=61_f@vFCh2A3K{$Quj9AVtPWKt8C%dbbi_lfy4Vsqe_|zOBoHZv2 z8kpbjICVmu`6TuPHV!)>%wm||y^y0sb3#q*Mpp(Wb@B48CJwy6wX+res6{UB0r&gh z9_5xrF1}8Wy&IBHjnr#M_33VdTd3%@ZJ>kF$0wMd^iNv%xKfzvDW{<|7-mt49k0oX#Ypm$z~%wBfzjptVj;_crR_(66kYB+`ixuLZ@7t_VtJU|-Ug9olJQf*r zqZ1BfJDVW)&HIb)Vt_UD=CLr?Yqn!?q>yUgj}7s$ahjkb7c8SIFSG^Ja-z!-iZ*4@ zneXS2KJ@VWi(zbsAD>I!r5lc4AlY2h2DLX-+SS0O~r|j_`cQ%G>^Te@DkP5dD=g4uOoL;$r9wPO?UVVr<9M5 z>Oq@NOd_{vU_%Zu&}j_`9=a8TFIYjhH1zh|P!ysbIf5Y_WJ_nQF=Hj8sFaB4=h zU(14Svz0xe9rg$70 zMBLG-7G&(uUpHbUedgppnCW+Ns>id?*hoI&}}yS8Ca!i!t^{9Hzci-?CQ$(5aYV@*qz$Y zQ*i3%@eLi)XuP(O=Y}?S?aS-}|Lv9ZpQmCxpZkP2dWbXW-BS`dNN<0dw@)vHwL1OG9&h%Z=m+q!tgM&)vk#GtT}7kMz92iflI}QrDQJgHt_g-Z{fg~d zvs}{?U)6NQxiLO(+SO1b^ui(}=KYXy#Nb(0QtvOa z$nE-ZU+g2nAr0T`q1u$u;b*yZ@)x zI(;;2`z)GvA&!ivGcQC|eC=|YNx{?eAZat_%Vj9V--^ABY4dz-o6&)^>Q zbQ?)2%YjEOyN?iFr4*`!>7JpNuyMDCdW{_u)KaXUkF!!IT${f$C#CAl2Z#09qC%b} z6zWgr@PqG~4?@kl*J?F0uf1i%;)Vsn#yhwt#GTmv3#k=}cV%0v>lDIPcxjs~6Dt{4 zE{+!!-uv!GZ>=4Z)-qr3V>+rYHhu)-&8JnXSG#M<7S4R|jBvS)c+}y)m+z1w85N%1ZsF0->a)+w!_<*gyg19qo$m~Lwg3EyUYVEzRxJXUvU)43+E z{9iR*xgAm^ZElUMV0rzKHx$_5$!3YN#S=T+hvlB2nPqiKbHHl>O#Lo>yS15XehRe9 z0C`e+gIbhxF6ljJZBA(tS~J>s&{NsMY@C_U zK$&GVec_u37@k|dNrsu&^i6Wb9gDUEH-$>AsYm|X@O*YiKUs=Pw8nt^cQk>BU9sHK zE82ZMpg88&YW$G$H7?_w(uX!y-Pul!z{PlC>Ai(X%|mnGnu~67{NOckWCJUKSAjZ! zso3epcr91MlAWy zQUWQbuj4zFnl2f7H@dDci(YXV|CNew%%7UOYCgY)&bu7#w-0;cYgT@uc9By$KzCh! z5;pPO%Np`;8t`p09_?g)I{^=uwtt%!Im=3tzHeQKw-Xt;#p4V z0hPYh_+NCA-QoIMX4Ww1qkX^o2$J0VuD~tt0h)XzGB(|L9!jiP6PNo)8stoJpC27k z^+!%A8O(-{X3PfD#aA>w!A_?XW}Q9HDfOZIuB6O&NDh|=^sI9*0NANR#8oHRIl?uI zs4jRde1pIgfIXSW(36@D=@%#2>6O_jMw_P|%7%OekuYnb`+dxxZGPW%ba z8n5G>FVId$UX2XLYX*`){eBpj%EVp_9Y=)7eiej| z14aU?fwuwHjB0l?O2FlvWIgJNqvbyYr$pF`mn+binP|+s@-MfN!oeJ0^6u0&J2&uF3x^k1f#A{G(M9vn&bZWCJcL4Hc7%89t$Ebq<-Yt+YK<~J zhdQuW>Ea(Jl@_}vpXF61iL%un5{}920SU`(UA3t2Y_LPBu@ltbj|p=Yoc$2)v1{C1 zX4|iu#|uB0S?{%=mwp6nKoq4YO;et7*bm^wNf6gSL4HJ?_EfkdBSS4M^7lSb=o(s;{6i`Q&fX_&~<*XyDDb9;`&qb+`va ziI;(@^)&xxG#*Wt-i(jiV%6%W>*t$XuyU}kJM@KWeKwSVjuw~nwoNp5YPIF*O?kBG zW->fJ_iu)TB-x-A=)_i>2xwHWJ=CbfKoro(pSAAcRii3ZL$+QaBp6i?KNt5bSiV+m zNrI8x*2E?IA>Pkgj5zae_e*BoA8qa8$K%nCM(|YMDr85XQ@ZEgcXGk=MW7Cl8ssGk zq1edb#3Hqi2xuWl$)&7`7{~x8fO_rbF7?9qzPp(PSrE#$Q@F4cXZt9kP0~tGFeF z4(YkhBw=uoi#l$Fc(dVQL-ofx+UFNF$)KZtNg(~`{9ncpPip)nF$k8UbkeFuMZQT6 zsR{G1mbU*A(&HMm1os$&fey%CPkY~1`#p51%T-PPs6L>7B$d&e+wo*JEx)Y+V|qI$ zXc3qV`(I|Gz$}5@y&W=gM)N|^pZkEFrrdG-=ehUr-;1k-Z9DlY=aw)Vm8cqI7~vqd z`%8^2W}@DTZ8P)N;eoMmvRpB$^>R#o6$A~U+kVv~s4QB2Xx`KM4r#JwkHs@dTh4q8 zJvIDjhxCU`lLCH zq|>eDD0qgCnnwlBgUyy;>Wvw98@EFbp+wuvnxIKehZJUc+-ZHR4#}Giyb}^L;uF?F z#&4mBcim{CHz&EbJJy9`ySj1Soq67mx{toX_4N9kvE&Py&=x?UY`ijcuC18h2MJu%B~!web-y zG27a-cv0y0Te#0*YbI==boC=iK~sJk>30RRmjJ%OA!+N^{00|wa{cY!H^}_%cSgT_ zvqXs>sr)H5(xvw*pxHdScNjNZd+y)G6~b1riB#0*wO><`?e($JZbijxJI5adnr#1x z|CYvRhC4Vu-uV~ps_wF}e@kQe2ihmdy!xHJLiSIzM2lSW|6Q)TK7al{3f7Oarx3SH z4gW=^|CaXuFVm=wTkn&DPeQ8yhfLxBDH9sw9bIi!MZaYJ0Sn6c4z8-sIAh6LYIbU5 zzpStKcKs%k+1DF72>AkG<3DAjpF(Ee(0I>-Tq2~#aF!>DWQ74gF*qC;=mq6>G?$TE zhKs93c*0<)^&-b*ij9rWc#|h&>4KA&?kfLc{g2~nNdC080SY;$Yc>48~+hN))Vj18{sHY!BMDc z91uu)$jAmmW)O)Yiw#9VB*AZnWq(Pi`_XE~VW zHoS>n6!Ah&y#D3HP766AN~0Q08d6OB>%jUFU;!dF8Tx67kX?iCH-SSyncE-bCy3J1 zmVbQ!KgnSEavxKuP}an5AVn$B!s-6RyIMS==h$@#JN-l{%TTW+lN9$Qi_5^rkQj2? zkQhT!{6aT(aaAMywXrmYY?b@R;pMta;0C$=s zkwfkgSy7c?M;_^5;g)9Jc3-%liOdjBPpVeKUH&EMjU&-@SBLjIOuxc4N9CgFy_ zr$|WHq^X2o3LFDk0g}gw$4_$2+YFgck$7^?F#jpCNBKPZWt_opGMPro409)wMA`Gz zjc-gQy$KoDXq-X}p2`6O1`ZftSoj>tHk^2ljP8y{%_LEc88gWV@)tpfVNekXZ5&%f z9xDExx^@m3K)A-Eb4a=T@9EFXBT0=f&m;Ri{+>Fooa7o#l#>yf+fQ-)9XZDZ@9ql2 zsyY6742N|G$N#TXA%^@#0jj{4d-4YPy9WeyNvjIx$xIjFStY+_AetbjsILmo_owYX9XG6 zSha#Id7PkKMMfH)TSew{v-*7%nQVAsH5t?$H>@U^Jvoj!8SP4rvjI(KCSE?h#qir| z@;{l|&%)}2V^V`(kQRLmCof<;jbD;}fjq44wHjz1jH*xrwfD&L6aG>$(CK5-U zD+<6Y2daUkz&fB5mAVehMRw-cvX?OUWcN=Q$zT8gi2r=c<477gevlejN5Fu zUPab>?dk~`LJ03@EU6|Fyi--vvFkof_;7?VKs+!QaG@;wnH2(V1mYVM9G8P|BErdr cyOhK!dSV+foY{)8OL`4&KmOWDx{@dU9~gl`1^@s6 delta 16399 zcmb7r30#!b8uxo;F7!GmZDkM(MGdH zGs`s{32`#Qu6DaE-axH1tu)io%6w7boq<`t{~7e&?)TmA_bYzCKj%Hqd7kGyXFumT zXWrlIwe5gc3g^vfnq?ecevac4fzgk`e1s1`|0A|^Xx4zMz9wR&{-g-S!-j5@+f@s60fqe^L0d4|8 zgz$IeWNVKI-+uU<25coPN-vVm#7WIWw>48izGfft(R~Q*Asa2X4`rbl3G|wbmyuKS z7uiCktvy)O(-L{EQtb#9H`1f>geco7R(MVaa2(Iy<*soA-=OWL^u9dL+vRXsgTzm1 zmZHIXZJW2yN$f(sl@nAyw{;UZO($_2ou!Z3~<>~=sKOL-2kFK^o zZ{v1FH(O$Lep3FUj%(#5MFKbqslf9#uaeGwI%-zQl`O35re_xRUTG zcf^q|9a9Q^0(aD36kVLYut~Q{W{7OMv56SMn|#F+G^W!el0sK@N+7#x_I3J#kS#Uk zokx;Kx6@-)h?cxfAB22OhS1MKqeIp>IDP-7@gsc2;qB?h9ofAu z_=*VZ-|7i}pJ6PV?eHn^ z&1a2VCT9l9=FjI z_D|z9F|~feu=}HWk^??@fnu!PXz691QbqO`8w11=cbrkOlKlbV`_vi{li1b1-!k&y z$MfrLyjmv4v?&CA(SNwd{+s(6?a?KMgwv5-qAR@J-qnS9MC|P#B60K8`S|XE?{=4} zT4(e*Amk;b`_MqqY|ANB9rQk+G0NzWLPF8!DSwC;4XC#=b7r2e_^h3X*IeG!*Jcv& zDx`NKyyW7muUPx#E2}j|UhLbhe6?>r`|8==CqHz5j}bma;vie-ejhR0Hd1t_lUTn4 zQTx+I28!>wWV)aOJ@UE;KibY#28!>vUaoXE%=x&4MULr{smk(McZYZXz&vhf&k zKooFz9;dlp%kiaXkR-&@`f>cy0UV!MIE-^5Jd5;tdM+}asOf{qzT_X&5H*;*PiI99 zBDM5DRNugne`B56ouv>o8kP7Qy%$wZ2GQc^;0o%@ygxP;9HVh$*9h_} zE$zBorEOPYI#P?#HFvwpNl+OWHvu~V4rN+Fi6%w&d%MQcFJF&2>`wcBb5Lq0F}+1&*<{uk3bnwSCeoY$?L zp?eH45ts{90JmdYNw%7+)q>eb?Wd%6*{^x76~aC*_r3%9MI(>cwT z7+`9#51khq5msm6IAviMqp~n^86H8N04tZCNiNZ55}8VCWR3Nt}~ z_?Bo5X~6S2;6P3$O7tOT)ed1h>xCpHl=jUKGWJkha; zY7sl>iH&fj34EUc0w1dvNMAoupx$~d=}i;$y-623S#Ox2aGkU6jqs%R@e`fSpRH_Y z@B*jR#Oef6O^Qz2T*8{=rFhJT9Q0_$|Gu zkH^~Pn;1drXnbNCR<36f6M{B5hX_r7$P=qtVnTdR$ATyl>#gOeUf^_oVv^&cr6x)l z%cC3|)d~J_exin6Nz9Qs+i7f4a>%Xr1yL6*d@M^;#|5EF_=#6(NzxGV0ev?qh5Sgr zPSRp+mXZ=ci7{x&0h(oqCa==ThD5TSRv8jd5oSX$G0;y8xx}0LCr{`%bpqj~+Khr( zg4#IRI8%_H;dQ<9`(WYk?^Fn!KE25&KK;K^)AG9`)j;M!^l*j?)Tinq8Kde<~D4X0_}UItP|OL`@e zLv%~8utClCO0zna(*}vZx4HE`my|XVI8#W&EFL7@upiF8*F-efjcUA(mDSJ2RLa-- z3Mf04!~(|>dc9Xj#d-VVX71OQ<2Rxku>F`)*mI1Fs~q9q+}WoG7T?Zmyfi=B)Gx2d zcS$$x%59(96q$x)H!`nyXEv{{WGykGeXXE26Rlg?>HO5j9Xr*`1ukfc70UDF8kh8i z-K*uDrxktGeYoW5jr*Dv{L_MQ*i?+$n-Rvu0 zEetj!UaGhC(qy;x3Vt;^Q#?{hVn(*Q=LhU}OZn~fwmzwAL4B)|i#^cnBkyZe?Z0yT zds}}s_p*QU6Edtaj={zZG-Pi_pk8rV9jiLPVsB&LtfEJ3si_s`?)apq8(G2y8&{o& zM3+OYmsc-o(itO5W3W(t*sjp2TiT{z0i#*XoLqI_WG<&SHp+K0Zk^*tD~Vfby<}6U z{SRHTah&|jB^%F$7jZiO{ab8tsV>Rx(i|Fbe_bd41K~pz&8c$EHhf@)(Jf7IRd=(* z3Q3+S8esqSQMD->$3d~LbDY472irK^fTCjB-Y2pmD*s38WgDN$Yletw`Dg4)tZG{; zEHQUR1FUP43wra&hx^Or)oy84yL{IdHZGOZZMG>=3v6+o2B~=1^JuK#n}5oxXnAMM zp&YMfg%@UWMa9GPqe)hNAg9@e4zM5i3fPAZAtLPbEa3+}ODcG-QkKcKAvawdM-s(a zZ(;i}KOs~|xHQV9P1V&DpeK_3E~&!Bnk#kr5oDciJZJMsRf(TrZy^)XqWzl#IF~fg z#TxNIv<%HSu}#_RBRgXA;>dw#Y;hb$og?HJ4kGyavcXo19;_qjnVjm%@c=_xQ=mAN z*7g0KMAPjV>B>CV_98u(5k^|*&5Qw_`1>@z-&nGZF7Nk@Zk5x|fzaO@!b&A3E$7PsjuDbqN_?DdgQonb)1n)zSP9* zI~tS;`({v*8QF>DAR-4%5&8ze7t!vSM&GCpu+3~>iR0*=%pQquyUu7ZdqMTIG%u)@ z>`7I+s`#Sdp}N&Sq7fM9Y>4lq_RKjcf_+xiJHPsRT^f2S`^0hO`2u7rrA0&TU3*E@ zkQ_!C`EXVFD46jErCG(Q!;ob<&QNF81agj!&+hH3!3is)o>8ySo!L*x^wa6@*~tmt z*|Y-Du+uXyzSZy$f*Hl^oQ>m=B@lmq3qz&}roB=_lZca08{aq{L#NvTI z>@UQS(KJOEtYoxnv|NZJ_vjWu=N;&lV|Mr#trOxs`SVlgPeS*AA6;i{>qceNGxoSC zv}Hg%;#?^{)Y``Vna%U6k9eq8gMJil!|t^GLong{>)i3tG6tx6e$Bm@)wdUD#(0ARFIkO8g4dh8DQ2MHZ|x6 zaJpT`U(41vL}3Sky@RLvFF~GFg?~*-UMUHD&6#3}gZPUi4&vMCzWkJ+RnC%mznVLv z#(j#zKz)wh$R83l#`z_>87m}Lg7Y0P2ABg3ETP#2vDipWD>&t;v~@JT&|qkAuzic@ zo+tWoj~o9a*voJNSE8%%$kr!_M+OJ!^1=v@LApW&3gp@)X;BX{ZO;W~1JE*hRfUZH!3pHgM8 zgB5hh=!_95-B=;~rV>6G7|JFuU?VUL&`R9qX_v{ z0mp%yX@vg)p&DTZ@*aGxXDAuRVVeJRBx}j1(>?Kj($}A!Lw=&Z&kTq>>w0LNDAb}86hX%lfJubU zV0IQi6B2ybrCTXCC@-a><7_QXhu*!k>X|b>j4K0Nqi4{k$Gw+w(>b!$wcvG}qN-uQ zuF=(CyyCo!1@6f4$f`rx%JZ8*e|_|3(7&Q-<0Wia6aTiI@U-D?TO*jVnNYS2r~-^I zV<*C|Xz7IOB%2ma{F;1AwUgRI8K=sKvo<&?0mhkNtm*k|EMYUmCP*GvXZ+3$*sVcJS)$FZ}s)B3UU~r*oile=l zreQ|fy}0YhsmO96Pzm_K!SNch-3G9F{|9KZO9`)Ask5|e_d)!i{p|wXN*{xw$)O!3 zIHkAjyAdadJGE~j{Z+cFcqExme=UwDlWEYDJtUx}X3BUH`X*GdTt$RoP|3PXc4rTlcDYK2?q9gOh>;1DgH6&?1rqnjnE;9adD&mq0x82QU4rCj4BPN1*PN+Xr@t69?m z82@PielDKOqS>?Kf_pi>wkfL9g`_GkcJwoOiA{9r>~t^28a|62pWU5E^!n^v4`J9W z+I>za`Gn@oNf^R7R?NbJV3DI2{jFSvY~MXqmdogGgI-a~+@oDFX|k2zY6;J-!h&WRvXsrTI8p3D@pY4+S|nX8RnoU12ysB`XM@);d8 zFP@yBCG&c-9l^Zugrg7U6~j|CwrozISDW{)@ZZ%*WyZ@9?b24-RF=Rhuxvpev;ECm z5d!jeAGWgmQfCvs%N+D?gs%ZLzy+Wg$OnA`5ImQ@Ri4ahu6#HdPow8QgLB=Y`6(on z?wvoG+@kUYX^BkPb}+vK{NNE{om?8}FR*bx0Yx2=_BRyOLMJT7{5-;E0po$Sz<*ZodsxBSrBdo#G$fK)co?Y|#qbmAEi9KA#gRzwPbWM#ErO;0 z^WV~4kork+1XA1S<>w}QQh!4#TT1no&Pa6@2P3tCj$Yi+y%c5ijm4YTB(x+qohgee z>zFbW!iHmVu?>Z06WPtImmn5{Igl8XO`AcnX1xGPXwBXwlL*0HZ&@&r(~xB~p-jn8 zD47VbWrvN*on`cgWfRHgbinehA#0G(v7N%oe*d*%9(u6tSstnM6qb?|!O@dEt81uJ zgN-lSin*nW4UdOuBTZWoOmb+>igZu){MKP{7HfS2R^6A00UEnfx?*2E)5w>zRaqhU zX##{0K`E|nOSPyAKGLf5>Tj22wzGb+vaeS%xE7VuS6B8S`)Je37&4DGuMGB(-!G>= ztNN4SG-p*h{x4nCSNR*b_t9F!Kc;t9%?mo!b`s}UMbqqpM(rHrUPDVOmPfC*ar(bE z@mh`0F70!1`qIW+tR5%Jhk*lCRvAVn(1^+-G8`_}1Y2 zo%yuq>J#kr@yqIWNDSS&W)gWmJ_cUYwC76#SmLk+g#R0`c>#Uv`Hkc}HEf6`XK4P02|g_O zOC;S`K;PT&92raFH|_z$ryD!eCNHGFZ0zQhxdN;B3L09qgzTm-RW0&}jauj-25cHd zGU((@RpbG^vuOz2mnoYKWF;NHIiZkguLRpM)Xwf1oaRM*i)h{T$5`vi#96Ln%V5-U zLHXdkHmTat-7*lpEHP~$VpWb5O9o;|Y5fsfL%-O3IrMR1LfNkAk>1P|^n(}j*mSdH z5V=gVw&=X}BkBG^I&;e?@)kX{WkSgBZHaJYw@EL$_2&436WVxae3BYooIv`}4KErx z2ehxnfM;TwMICK8W)c0zi^JIY>!sefLd<`uuMgYYZ$$F>MRe0kZ;%k0Se-xy)6vz@ z;i+u{jJl$MMfa@xQA)<-_Z;D$c#b|_{WS5d`M&xnA@^#wyxf-%Q_UxI1|dx}WqVd| zw!1c4zDs$&$T&YTLeLMjNwetc?dfC-t=;}rr%LGf4EP#2483C(*Szw|ZzQ~%>jGT8 zN_G#omTOSJtPN{1J#D71?l>O%(uau_C8{kaNSSAsK5*iw2D7+^V^A;=tOpmdJHrfj!ED=0nZFS+>XDXxLBx^RN*m@>R!$G@~*Q2witN9(Wlj z0e{6q-=pDh{lk^s7zT3>X~Q6=p)b8L){Dt~wS@li#v26N$2a?hJl{4VN8d0)2(_db zxrAS=N*MVB{r1h*(G3>uPWNX5A{48a;%1uG?%tqeeWspf?TN(tJZVoB*+Jjjlj5a8 z`i!MD=l4{Sh>vUojFC&^q9|7zl#SUi;ghr>FyT0zwRe2vdRw?i0t=etyCSP#qUZ3e z%1S``68hubc;7Ue>YDsOhEXowrh#vV89r}IHT#Ie?MfW86mWp*ivoLL*AzD``!}n6 zm%+jg-@m4f66_K>?%RLcqzTJKTAE;IRj&r6?P~JJ7yW}e;_qj57ytodJwEw zFF1u5LsuRMiwyQ$0esh}5Cgz*5ggU74%5Bp(F4;4HM>qW6JFWur@YgYYLtm4hf+9Z z#z1v*`cJ`~@5x#&Hn=rK4b~yXbTiJu_xq=L!*q0ygJGUZoxP0CJ*b)Vxq}VHmPWa_ z72@|G9_-0XE>^kqMOLf2ySzzeAWeI{0~(o;a&aa2u7J-CGdm~?k+WZP%k5{=2o#J6UVpw#vm^==&M^K0|$K1i3hv4mvcP$mr%ng@N~7 zsb-b9=uyhA^yZ;Cq(6P?aPP!VP)LnMc7RoY8xx9bzg#?ut2#Mu!kA2;)61i6JvASW z51x;O|83;)5VmyKjCMI(65@}zTT>U^$kOv1GZ z2`KPu&}uZAdsdaWg&sK)9elA(C9ZI=K61~xyZA2JIG%ogB!U>JbR+?{jWO@VhpE~* zZSekcwxN~h?gSp-P;cR|uMeH@UM^03d*53?F43@~Gw?8@;^;Y&MTZ|tj7x6&{*J${ zOVMg;varMYJ|^drGjY#|{_{He&pM!X8GZFwEbcYxk44K`+vwF}E8@R3bG+&gIQ55b zM!yb3(3R$|NLJ187trNJ?Dd37>`dQ$KN9alPQ5>xT&MoExnwgPTWd&gKx@`=wxJFx^u{JW1Y2-} zXAU56#Ys4js5C@;n!Z~bQ}LwdiGU4L#@V@?hDjDdl06Uz7Q+K^PgNi*a7*VJxQ3P! zc(Oz}UR_vL8)@`{XUbp+z^Y(|J5Z8}+&px~pkox_X%G?QWvB0uY05lKoMhLVwE|0x z^5j+a$GpgLDx7#CeX=vC5O*_q(M3UpQAM2iz@|5|Icuvn5V}L%0nnpt)0=%j+phHk z&5zcd(1tR5%V6(G*iI3id!OUqUrv8N@ih6A=F}C+u#tJWZdBrPu9DJ3bTF*$S>d_! zM8Yvw_gP2;U>7Dga#~ze=knq!)c0g>Toz`X43>>rL7zVP7CXzGe8#H`Y+rz2d5)~6 z=PVVE2~U3T5jK56r-F%v#-EB0JMGfp?U6>fUg{CPz$>+|&w zSL4#Nr2ci{Uqe3XE7Sc3>u?F+9bC(`RE{BAi{`XS?XDQT&t*+4*~wxv>4ei-T+yyP zJvQ(Sq;yA0slZYW(d(xd;lTOK$FKXaM@DKOd1a03JU!ul+ ztgTYaRPptEZK|i4&S2*vyQ)Z4ik)o=@g&{wWse}yJ<9xc}|J976LKR(`5C^GKI<$H*-6mA?T64jTuJiLoYO@c>RpJOt8mZ)SQF>L34cqg%4?PI zg2uDkR*KV3or%(ka=fByX(Rl9{_AOQyIa7xn#C8}Pl0?20tru(A?h+uQ%!4`4~lw}rXv#IfZL_s9noD#TzE zg;)9uT1z5&MPgoylAcHf zc~JkYPI8Uw-rB^)>Sp~kWlCAFSq4|lj@%FnYuK4KPD8Gt);YFhGi%1ciUq*2)zo!4 zbV8}KWC^@sjW3{gepS2$MK5yRm}#(V#45eCcoX8|;AA#f)*-&Ecmv|2kbdEgvgfPW z$_o{sE-zjKY7VHo;GJ9s%F5yjPzKU@-yMLzCgO??&ip}FBJkejnJa0elvZ6ak-k)W zwMSQGP%hU0Mi_LLRnHp2M*|aqb!+I{tD*U64&A>`fhAD>ZrW5R@8&33qJY_xVfM`O zB2c0o%uMDuJ&-mD@el_q#xsZ?gd?>@@~7vn4k)%e3~>JWHF5A+w@L$@38%7!(Ku&F z(ki?5TCQ-<`T^!g@5YYwUmP8w-pL$e@<-Gb2iN09BZsG2LD137*}=m(nU-2w`h7I{ znQr)gbj3VRAF{o~a#S`2z>=J-POxNodxthP-W9e=uQ>=b1)$x(a_9wrga_a|U@7H} zAFLyUt5#M?$50{lz!ks^u*&KL=f=PL1^Nh^sq_}+J)IL2k=G)Va_RUVCPzN5VX+>bFdQ6%1|$FZ zZBA*4bDK?{%5|HuWQa)Q@$;t_twVfznNwOowb!x&hdJ1cmnPsT9_N&DX!*57(v9xA zrt8`n^Ne1&F$MP^nNF$Y!`^09!Ai`6T(=g<3nzeU;c0e@t^RR^jDsnxo=?M+W58t~ z!*e&GwfGjS*ZRVs>oop)LMJBi5UEokF&i+hr_WxG#apk{*Ao+7!K;7?##t6OjzO)s zMl%*^j6<-pw>IKwPP=Gr)9K1H>U-0s>uEja+qHtXhKqAc18gzZ*i6nkms1+pPB6WQ zO_;k;Caojf%&5=Mw4ZbpEOTxhTjGWo6@tO6Mr-Bangk=zt}8W|{ZM-eY5s`!vX>yv z&az2qK8PpVJM?wN10k00jUu+7xuoAc6NMf+p9ZP{sa9U95K7D(EFuS3-cPoZ)Q~28 zX(S~c-s_4>N=wYBa&Lk+M^0%7k|UbfS1Wz+Q#>5q5jPTK-VU05qdTsF%5P{x4%)P{ zG)vr4l-movQk&1157KvU#N?cIrwJ_fN}E#PYRa&)=i=Cu`Jx@K*R-wD%a6jh?OZI` z!3N>Cc5FCzv`S{X7y8!1A}2P>zCTABSc9@gfpCPR6y>nETzZy{!qG! z4S=T$AQv7v>ekclH#Pp8OH;0{f2(Sbu|--zC)`Yg7kd3oEjEhp-pmbN0rkSa)fYm2 zUrKI;;T9s|R-{kXWzJ(bR6TJkl%&(Kw*~~I!2xs0tTD>bztylQhVHqgHALBT#_;@c z##X7=_PWhGRaY*<`?tCV;^bw(#4_^XO`o~ZmQ28E;?u-~_g1kF>PMaVP!c|33lOV}c_JQoV-w)RNuE*9YAd;;##Y^)>EnL1 zMrE$2_iqow`ak$iVxI=5L#lE=&gVs&Lt5tUXooKv*#+X~*i&`nbI>z%AGN?6cj8o` z4wh+~w2XdnM;lazjMyAmWaf+-bBlC=I`8Ok^`ZSG(znK*h4W8_rbSZI++POyp9Jsw z0AK5rdem(F1)k{vHTGZE%KYtZu`gW56vlH8q>pLU?-itms_wmuy9M*TyW}=~Q>-Ud zHItgJDDmr!e$p;Q#b^h|n}7rD|Be4eV>}5?jt_DDhj+#!*`PnrSo)skkup`%nM-8% zC|j(^HT>UlkMaxP|4Xo@*pW^=HtqQzHvKQ!U$<#+>y7uw-lt&I|Hr1t|F#K*@rkXn zs$(};Kg8H^y@Na2uU+wEBW-tSWoOsdbanqClU-eJ@{y6x5!QVpBS{L`)#vME-sB=7 zubRH)NeWqOQmV+iK~5eM;!rLVXC%$x`JBezRIegOWj{Y(H`j+eAtOgkNBl@+#Gdy4 z!gXWn&}Qki_8Z0lLw~h~3rRw=wB2;wkLdcYZAYgcT2ibR_8KQd?k$qT+3J6}r*Jfq zY;Benwv(Oxg=@w%h|l$i-?1`bW8DCMvQ#E>JYRPrkgOp-aU0;#P~(C)ur51@bdr%R zrm?{!hO9I#!i#4A8MfV};hsmW%~G-HNHE+kBTY@gWDW_h8{C;FGoJL*0ll zqEL{Trl%swAYw6X#VZh!YWg&iWRbu+RTS|ivWXk&I^pfKLVIZ=W<0z>%4A{ftN6tc zFLcK1U`}kak^Q2SUw2MRN=QI8RKE{g0vsDmPr&VyQiktkz_xGFl-@GMgzXj>M6BrmQ%U?r%f(Obu6s`=Pqk zab&YRAPrC1Wdhgzm8PB6&Q+!^dXh>ynF{qJONQu+dh$HNy3j=On~d}^$&<-6*|u$_ znaSi|0hLhm@EE6oyCCz0syZQs{D3l7)phGZid5w9bsI7WZj^p8_3cmYlACq$1IP@S z&u$3q09ppty)uaOB(g87>OOyhJnJpvHrFKy(Mu(Kc=PE^&3gX5^~G*(kL?C zi`8`U7Sr#e$g4j8vB~uEXmb7!@w&NBl1=0f1e0tGiA{^QDGN)cC=2%jH-NY)x)SF1 z81xL`i-Da$JwWm~@#smeVX0~C7?MbAriwA-b>&c0Qa_V+EE!LhnU;?wDYBt2)Eyj4 zx)9Q@?vtm9$vdHkao(J1Jr>R{ojPM$kFxpmW=<=0A4ewqyZGLH)aoYUi z*{0%W$q>_9&l2IUNQCiaQx;9{Uczy8K9k7_@|R>ySBo&_?iZ0(#b1*ouK}$^Wu&YTfUp}uO zP|8v=$TWK?nfj+|;p?SjtSNcfUufUrWhAQ;b6-1@9M=xie?02z-CIm2mXRm3wx8kn z7P!3Q@yq0CAL32{s6CBs%SUjq;5!Xa0nOkkXLNku#80EQ16q9NnDUnsL&+ZesCgQY z0xSY91HFOm0Gm76Uk<(}0m_pc-w&bLpW}lf{(R3yTZWs?Ehk}rq5U!YguSwYB$<*| z5dEL7VN> z;H-}O(?+(eBo(ILSCNRi&8x^=xeq&Uvm@)&^`Cd*o)zn4?h+t2e#DN*N_DA z?C?O$?Z6_S7?=Z$2XcTkU^T#+Yc%#cgMg*LG@u-q1mpv~f%O36BkUjkN>Vv)+y>LC zb)-K@G+EXWowB?W;jf#nufr}W(L~n&o07PmB!q5_g-$ITY6zPVZh?-xji%}A$t$vJ z8%?hDWQ}TlXV?&iMZ2!*c{0+cw*$TS{5W`*Cg1=7ga8`A4O#Z{Lj;^2@wEz$OGh{g gVV22%D@jm1#Qw!}eIvTisI7Rs@}C8@gFNd00E>n%djJ3c diff --git a/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin b/Tools/bootloaders/Pixhawk6X-PPPGW_bl.bin index 37f809ca81c0ea8a7bfe0ca4bfe6e964065db146..ea37a306fd6c5f5326be60f9406e7a519b432cbe 100755 GIT binary patch delta 10907 zcma)id0dp$_y2Qd;~8X`5!nP}7LY*%K_zfYM0waWF?WdsaT%ZzP!w0(g%pLZHJD3Q zW?*X2h~sET*{7_`0=G2x)JDtYF@UMEI+^3=Z`P1*PDCKx#ymH?z#7#yF7EL zRH+?)*Dxz}P;{)LI;ywOJqpN3 zL6)#1l250@C;AvcB#2KsyjUyA6();+!`uw=xiBp7WHaSLDJV69qG@eHlt2XVXZ5I7_;DI?#QGO6&KKR zA#LJh&&y^??VUFM+0r7f6gm4nNtc`w@3+a>FZI4IbHLN+pwx$)#RpPkY^{D1{jLZq zh|+yD%p-H$Ps2D8_yoQq>7LcFf?V^AgG%BpONKW|mMj>u$O>5y zEG0W+Pk|v@wAiY?q@CD z>HekihMp@%YC4n-51yer`&lJ4`FOFyfEac5JB&F4*+O$vOcLXG|#Up077aVVG` z>SZNrHF1^U+>OPDvuPX^I)y^TI2XuMeQ; z46K~5VlrO2xNM6pdX+{ysC;cA zec6*;Ym3l|#=xM%ZPdt!?7z+(7T=>b|l5ld{-EPkJJi;-sD-)k~;QWjLvaNcjm9RE19J52O?t6s>oX zH;_~!b<{~+vc)j;OT!pirC}h>jcp;izDj5&#=fzzmptwpk-5co#`Lkjv-~ADcBAc% ziJy%$Ln#$1H3L&+y2~|U9l9s9Ayd{C1uREdT%D?xInAYXS%4)r>UUU z!3{7cwh#8wEIVixMMr4Qm|df#Y>8FG2$=97_a`2doqOOI-|i^>Fi3#XD=nfYu7ZPR z2?cf0S_k)?trr^Q;98n-(-|dZcGk~Kl_>1ol+K7HS6s9g6bhRCqf^Al8bBH0;1=8Z zXH)&NT2;){R3VCu?wm4yHm09BG+Ij2(L$-yRMI*Jcbg0utc0N?b8xWlGfQ7>G~?hx ztezUtWtmD`$5Vt<5B3j#WR+XN{}Ey9v{cU$cM4sFkEklm4kRVGPB8quzaWavqj#g#beZKN&klwj{7 zaw2}82QPX6vEn6)-n&R&JcI%9_ek$2O+(eVx8EA-E8*z}Gl_lZqVA$4!*<2lJ06=L zLeQ#Y+!dTDz^GuP?6!`(rlCy2-}0Cg>|(X$y2+_38)zQ{g@_~LhL3}KvSavX@PH(b zQ2O%{tFS~ffl|Z_rRX(y>{*2vOID9ahC1@Yh>3DuW+%%0gt&(|Od?;N@3cikK74t+ zlrQ(o0Xm6vyljz9!yM0f~0DTVvv!6%WiJeUkci>7PZ?y0g|9@mwW=5lRBWQCfS}!z(gX`!j$Ja zg^b^EslvgXbO5e|(@0-3(nue3(%+Dhv@rNwzbowrfQw|_*vP(oi`!%qYUEpFnQCdPDL(av#nm-%VU8=Ci#>>ZI|`Tr}A=>9~~Vt(pgT63LnTmn%>0 zLCQE!KV?d%z@MkjBK-ar^YcID~Zd8ViU=nzB_8I>OgpO7W_gTy@lHPVp3*r}nafJ7C%+=pj=g@PKR zFfHNl8AXB=EBEktVKUFZS3uq_m?7n}vNwS4M;;c8cWOz|k9s3c7|s_g#Ddq~1o{xB zHxV4d7wK3;CE_$R= z{7Sq_^*+4j@;aLA?nF!!KdAw>)pEx^iZwn}m zU$c;Tx=OA(Wtz`=N{URpqOXcc@#;f@+C@aQ<}BVY+SY`_TO@exCKyaUTN@-{QKt6- z^7Gp7Jov0;0njfY<}J{Fv`zr7Jg*k%<^}pg>-_-sky9JGD$xtcpBws0+?L@=TSj~~ zK61+TU&xbskMceM3rJ)|1WX{)E5ds6dS1h_8thB?tCS*tq5hqUp5XJm&69kr#&-B} zw`Jtm+Z*5@8MP@yjCBqyB>9^%U=caK>9oMLgOqQMaYyzg1n&~J67t>VH5mI-E8|@G zz?)ElA+?0OUAY_XlkhDQU3tb{#KjV_VapV_p})4}bAWI3l~r*71^RERn*}}nu;NHW zI$|3dh#r1#TPL`dBE4WEPTVcz{rA3rTry4M*9s=9;7Ml>Q$E+)l0i=B!bi^-omAK)(i>#kkkMM`!La^+i6lw$8o$rrod z<~Qt@KiDG4Ku$@i{_F?Q0(T)RHcM{`>*BRS_DkaVk+0|O&gceLjOk(qud}R<#C{YP z$=BG1*o*iJu^&g~J4{Dv=tl7+NxA@pe^Ig>)6_;+_Fc05qe1?$4(v{Yh)wRKG>=jCSW8LbUX{dc2?o|ulE3$LSH77LBx9D4vwNf9E`d)nK~AzhNp@Bk zvxMybBue~YlZb64*FK3Hu^Ugc_ZlL!0i{Bg70Mz+*w9(?OtmokzDf4P(^J^$%Km8f zQMa2!?0aTPa~;c1n!7r-g(U9_6Hl?ZvbAKvzVTs0ZDQv8hQJh1Qh$kL4(<(y2D_hx zwJNbzkr{96NRJ@*_a!^+%s@M{myn^KMtfNul;#l%X;26k86{+&k`E~@f;L=jH1{n*8$rOTiR zD0cog60!lP z?+)rq?rztMjHnxjd;O-mbkFbX(G61eslCghW^%XgO*l#>?vD-Mj^m{;3h;<6V9()v z7t{*bwRYa_Y-gQHyTsXx>7-$Qs25|WG<&g)Vyx9=GkSl2uFoy3DP(D9jo9v1z)og; z)=yP{XYv}Ol=ZdesamJ3f7XQLqV`mf923>;b^}6 zDwgfRMZRY;rI0xfPUmteQ>Y7cK(&ejMx7I82I_(u}jHs`k@1# z;(b560o1?<3%|M#bHphWo7JIdP%^XvSk}f@(ITdyyVTVts@*KVvu}OaXRA zr-BjGH{D}b2QDL1j&w?fWB4z@tfBpR_SK^&@B%G2dO;isHHNw$v#9a0O~KsC6SIkA zsxiiWkOQ`N@x-i}ylYfT__v!?tH}vth)ciYbc2MAAoq3aXS@DG1Bx_VQ2(|pvU?#di6fI(JT0kLd z;&Zm+_}JRW=Tx@(&Q)xJly0IMqt$Dl%FDmeQW1iyd>LaCv42`ACzsbJV(cXJN2Oe4 z%V^je@T^tAh;Q-%rZ<`TWAKPxw&#+fbY3>WEE*zf`3HsLJXN;QA}6z_lCeNfH~zBK&fRbh$Txv%Rw%4VG`9%S zE+_>l?VPmpZ&N)gJ&WLnHN_}R`$H+k5^Dz;`%7RMUuZ^%*8;uPg%=UGxZu0`ks=oq zy53>ucBA^esGgsT4z9JCYF41^XoN62zEQynDF=4|gS?%qz#ffh_}E3#%-&6JKvOf}iU=JTzir`b94I&sx&?OCTOZeOqE+JxOheDVyD)&cla3vD(-( zZLiV`6=inh=BXPz)AlLlNKNXvtrb0Sli>EBR;P4FPI^Z)HuT8CH)p|zO)A6%7ursI zX{YgFg=&6soua9AK!+k2L?&W6f@-X&k8cQ9Q&o8wTPn@cXa`q8JEYD>sBa0hCJW?$ zkd>`{h_+QG<_~sXlNGH4oVhmA&>9S_q_tHIPe@y9gaA(vsqz@qmHV%qlzLkSouMwabC*fzxruO_EIFqHitIQS14GD}bK~)a zE$Dn|(EA+_{aY*l%74TJJNi`Exv|9<)ZvL<_ytX%pfnIB`D7 z2|^21#Bp&12+4?FgXZ8#N&z>~i4;GQyd4SH{!GM91O}J!o(vvbjMaEaT%1#dwXfK6 zOCdtsvKjULl2eJCv$os$5yoQMM ze??9i@(&TyuXXqgQGH1ra34=-B{$Ppf$P9ABvE`e0i{08nZ~qnL&-0fV(=0LmvwkJ z-+p;O8E@r8+^D}q3oj#{BBUGeqXD82!CPJ7v^o#9?2FN2TOV81-RDYiOD?ZFW;Swb zthuEk?8{8-OMX!{a<*D|+cQz3E+z}ur+!+mM`4Tf_>8aBHRT zJ-D6I+QN<}G86EC$8q~RlsA)^$0j~Py0mna``EhDNw%ZN6?Su#Hfq4_77E|O<*4J; zZkhfzUdt_V>$f0~5yx*6UgkZ_53#hepzRWoE#0AICR( zqbIdSAN0`aA|EWraC&t@?(=eUqnPnw0vS&x+!%&B2FUp}Fvjxc@er(0Qxt;K2+Q!} z{4!NA=B9WirlOtOVu{9)O?9-Hb~nUT#4tAQF`iLZ8ExEsTLG?@f>}210dZUno9Nds zS-3$a*f?cVY=bmy1;#|GZyQ(IdE6Am7)`hHhc$?>ueKsOg_mpN3XYkZp8IDETEct% z09vvW@hu`Aedfj}jXl!VD|?_l6UnaYVLka8H?cGWYfM8-svsAytMKmEaXsAgWQSUt zsVy)%@Fd*MxsaF}zHphO-iR4+r$foOD5wwzH_RM-lMn3tRI_nf3ow+1ZN*TIof>EL zYv8$SN!<;#a{)cTreuwywIU{>L5Ak16v@z(L%2CaG`OLw!eZQ!-iKR5L<5aEeyqHq@LOk74A$;^a)&Vt?vYk88owjsPDyZRCo3N8oLQOk& ztwVzIXkoUEd#^K^8JvS}_>Nyp>H;caSBn6@U?`ZH^LPxP{g^faVTUP0u zhVHv6X}aZ(U&2q{ihx;!yOo6ZiV?p@dc9$`acqYIt#OOCacwy3Zjlwg`}UlAv@6oy zL|xAio)u)@?+W++c14k_>7$AdwQXE2Irn=w>>{?`l~788Zzo4Qa@e@yf0QjoWx4#E zC>2JWXzhXH_j!&hPCr?~Gu-g1ZwDyvUZk7`d!pg8Mgbb^#`G z_{#*tAK@>>*sWZn<9R#B%vNq6b}O@#ia6cEKau{3hpsLM2cF<(Lifn|m_nq9R=&|r zZXX$KQuch!>2dxxM`;xeZJeWnEHbI!A=z#U=y9WC6n;gESF~}%NwaB$`(6~@gP_^FFd*; zh7a@&&vu9=w{=kTuuh5|hv|#>Up&72G|Cz+|H}60uG{zm&qzM(@CyC^C7)~mFG>C7 zjzQowBI$n^@xOTgcO!BvUIYJ6Mxg1gstS`#wb4|I%gVA3WBfR4C~PJRtV%(Bh5kM3 zp8~=66=aR$Iwp;?;8l^}`?n28L~tHpm2Q&+@MEpPD1p%eY0KMy*FQX(8N^cX5wLXn1k~v!dqFJ3>o$48DDX9$@d6hR(3=bwd%+Qr@*Y;3jlcZaiD_Zu`}i{% zn(4(r9fc2GP|I@ux`Y1UkPOG->`l5adP8DlAm;lbVw_d@FXrwH%jH|Y`$ECMU}0$w zqaRb)G>{2L?ns?70K8$6E-nBjf~#&*0QUK*&KLlL-096-I%JssXy^!lO+t^@&NKM+ zk&1e+b-O8Kv+kW>hz1|sH^DGUfTTnLTln-n1u&Qzt}9@(01|ZtYM3KfRjoU#hKn9m zsBZXD{@=XKBdQUN2uP*a&v7Rz(kUlHIJ~M$pA5Ui@#vBm-NVT+9nR~Lr$D42eyd^86zB~Q zW2l}A_!G0Jr~y$?y5Iuv)y{%a!aPf67tYkq zF2+IWvTJ531nN8&;-bY0Ry|~1uHNJPzL=9u!(!}FJ)FSMOhF{UuRrcw@i0(Ei8f+x*_Xe!M`T?>Hb;= zzTLEQFcR1Ep41hrhwvBKXV-&9XI&53qrSoig2RZTh%XU)5t|X)5H*Mch&yZN(gMuo25W|%84!rxb>B04ZE zdt(}7_;53Lf^rlF)ks7hVlpBJF%B^V5sE0$wN_%l6>ZY}Q3*rEIj%sr>O!|*?Df|r zZ2`5&;rZ!ARBw_);D*a1PtmoS*ULg4S?oPU9s nUn`=hFibNrjnx?m1dBwtQgzkU;Mc3X>!+L4zw5QDB;)@9cfvb` delta 11728 zcmb7q2~MCxI z0WwIGBfjY>C%`&WoG1pQN1Q%9Px8fS(z93_K|T{l1|O+o+!z(3K`;!<-e+zwfOX`R z5b{Wz?sm`Wuqb#FNs-jK6*}BFC4Z5)Nhiv8I=XX=O3A-SilsU7*%N^6-d}#Gf;31q z@HJ_crg@*SG8*5^>?iX|ebSZumn2JeO8S9a$saQLyA^=<0Vkt5=xW}duHfG{tzqAh zz(S(-90C(bf#;8qLgKt~Ab@P}@`c^xW3P|lD9Q5P1f}GfcLKakd=+Uhh2$v0U=&%X z2!S`qHpOG;Pc|r1{UytQO&rFkV(#+U8xBc1503fFlmC|dsVs#9B&TyEl$w@zmWn;U zZTHOzELR#kr+e~uh{3lTx=`!84&EhMe*4@)Z7R-_Pa<}|=`fxY`;UXQrmy`q;G5}G zah>?@ttw8EDa)w6qe$+|CzJMo!bRU;B)%KTsKTl}xM7b*_J%6=bT9siLvQYD%v%L} zrs%!+Qb&Ydu)rQK{wq6LIHahZ!HbwS%f?q2m9BdEAy1A8_ezHM)KzwJD*gGzcxSIdxFfjO|0q;#Dg{Y{%lqpXTe@5=pV{bsQ@|7Dw4 z<;|aI%jTUrZywsea+7k(pLLuUUq&ul?_hGBPD72^jKW zPy*zVUxNn02;v`{1Rs;J!3hve)&&z-Nz@^M@mibJBHqLBbDYO4OkKn)z+O@@EQ1S6 z!n8?yBF$Di1%s1ee5xfJ@WD1O{ueSM#6NOOt6SEVh~ z5W^;-W=;shCX)jp)8G{G4V^DnI;FSJqJ#AJ;Iysf1GJza+zjE$LLGaXniw7DR2H* zEyGB&y6UA_K^5D&E*&hoq!{YWkF3S#ERE_?8=|ZreE@Q^&?e=%XbCdLl8o>g&=Jrq z#JDfgguo!vc1;+_TU*tfH!d$VIT@i&3T?k&-KaWel_Y9-k@zbtY4CE_16z^9sPtH( zPmHy?^a!H?RaY($*Y+N}gjAJJ(zAV1&Mr()M&=_RdR zH5B@K^E=vGEOeyfh`C$BB7cV_L=>)4Yq@`Q_uv(d{19sJTB`)eRQYtNq z9&(ZAkyIn~g^N0EkK@>W12{HZ%Rzz%{|zy8SA&U|yT?N%dDuOA;u8BA%dS9Idp{3; zzWug^u11z))T(d|2OA;xUskcggMY)0!LFo3^x*aOe5}&}dhmJnU9NgJtWUB-<+A~L z;9QkOc7wrWTVx=_lj_Jg2qu=uNF{3@!ZrM@PlkkPBfA}HpA`(@Zfb^TIY#5b?`gka zHU&$=SsVvLG@NII2mb*n)~3RIV${a?PDS|(W;UF*DI$~{4fQMJv33X~l7y%j$RPz$ zY8XaVMnxj$Gpt9FhNuwSMIS~*ftUpLh{QOg^zeZyGPXw=EGOH0OiW0g1gucqFSD3a z=tt>`IPur4rcXv++_m!@5^m!$_inxat1UJo2HVDv*yt+Hv zZ>{8#B3xQUsdsD`MRLHZ(w(_0>vO@%ET%2V*uvWsS{e66gPiZvF3~8O+wu}|MWr+` zVrdo2H?%R@z4dV%mGrm$PJZn>%4fbMAS;UV&y*19zRv05cjSCmG9W%aZk$ELu^B&D zN-%cI5Y_>VDqu3O`>=ku55u0ul36TDet;$2+q;n+@xGul)x;}78i9gEOORQ`$@z-bMoWJ#`H?a%9f!E7{kp|vDi>G| zp+ig~!v_w>i^aBq```viOHv0?i9^_;9mS~P`ZMejyb3KwEFfBui5tuMCAE3ig69}@c@gG=g5vNd_MNHUE)NKRyn z>grLTOCIT!!nxC`HV@dodE~ACCeNn4ChKS={Rh7#)0G2@296I-ggHbQe8ANERh1VT3z*bGF#R5CdIx=SjTbj#?F z-$Dv9Vmma+)(iqyNK9s=`c#{k3pgfMIfbvBfKNyr(ihDv(nno%4Jpfvgk7fXncoBa zK&B0g=}vpRgT1f?!1lyx(jiI^eG!src$j0UE-)P()=LscWrrd?5M>Jx>k;bLfIW)k zUx+R!pMvew&K%^QHU*BV0p$~{S|flNh9x!sF}eBDZ?a$%&YwoU9sQP+Rx3!xm~2;V zH`zYsn4I#SAWoAhWB+ugR2Mz4F?!R>FSm&TDa|4MGNJ%663v!jxzAKM!6fpd&5cM- zMYbM6o5h8u-jfD{tBW!+H)k^3HC@Wd2A3n+Legt;Xn1lVnnFxM@Dmu-GSpjucpb45 zdFe%_Hzt1|@|%x!+Q(@uA0z01LyJt|c|F8R$}cMdb|CWJ!E&D|r+|oD-5w{+)572? z@zvMKtk{%XOfKtJxYMe>7}%A?q^PhrXvp?LgC}LakIXL-*GNiH0&FF7i~2|@{|PY` zz3H-`eVz0wele6X$G?uN-7L;be)LMIDBUL9KUR`P`HNpCtBYTe)9M}+`HI{x&URV3 zVM=*DK^#RJJf;KNg5VJ4hz*F(5N8nG-oSZ6JT&c?K|o2xOOafHIO<}jmd=OHl&zQn zY;VLE#FQE2+)PJT$}U0jB;qzAqy*S_#N-lkZ`RAMAykwQZuUHvN4v?%*|S`=??_VF z#11dX_OkOXL8jC+XU+!zKN8<^lOMILD#i7QpzD=}yR4L4FMl9c*MGeZeR2 z9WgFQfK}w~f_4~A8W-M#ndH=4!$a?&bkAA%U?Aw4*@BMbU|oWj{Ux(V??p#&J2u^0 zBmp$>aB)Fsv;&X5S&TNIPRu=CtPDS8nZbL@N-fmT`?JW*w-1W?mXq)$=kTqgc}W!H zk+7v}Kuh*54UwHj!vV9&*`?ol(W-Vfu>BCzW}9{{6M;MB?LoS3w&~#V0D$+%sTCbc zxP9JR(Onk25ZH)?#Bb#Tmu$~6N}9YXLII|cm{rk`N+zs|>`d)U!nR5rOT|l!s;JDg zc~xidd)DV8+^g?kKeRn~AvwBw1?(UxYa*nmbGD2Wtr-bLgKRf$T>2bzpq_W=-+v(4!;+hZ=i;2}H^QxI>=B{Scj=`yr$F1h#qUwBIYx_vvi zk+Ki^xYM3aqtst>$>9%H(*yg(57*0V$Qd%vbnZi)$Wz3(I^{RSRf&2re~5VR^!MJ} zrZc+Zo-XC^6_;N_;&&#*P>recfSrvvhPaF~^DdTyv~0EXqAW`U;y)S1w(%OXJHLu- z-PtEF%8A1Q1|Pf+Sv= z&+YC7mk4}35u_yN<208-m-%Gx$GxQQ)Jpi12}%1TQkrRZ=ieu@KFN;kWtVc_ z8H3Y7&HO1*IEB}pS{(ihsI?BY3at1Bk8~Wl`$?M1Pt|-pX6BRrpXz*gC!>9ULcu76 z4;droEo9-R{y|sp9?EDh*NgdIP~rkgh+LhE`LpD+PYa^VjxU-p@zmrYz1yJEi}=Yl zDR;;y<~N}9sd_no3}dL}#QaK;-%9WzY4$eTQD)*cvU!Pk6#44O}K$VEoq7#|q&pqn6 z{HHzqJ+^XwsFTL_jz!FSqrKZ`Z@|-j-AGc^a6IeRRAqS|b?A(8-s0%+$V3{ero(9d+DO@k3O0H|D^s=0=Do#-==U0#q4+lXxId*s}j3#4E(XxwZFJu8(VNyXT`P3BFrK^Kx zeyo@h*pC}OZ63IQTsHOZZNVHst`RiAiA(-<7Yd~544>1gHL5vQ1^jJ0Rik;1zo~Jb zzld*^%Re9ON9_z-fUcv>8CZUQm|-_AAP+u&8D1c%)mb9kaW_}L=JOG@-9w1=j2hD% zX>y(=osPu&3AO-p6emsx{*^WrCpuJnhkv{0Lh|yFHrX)T{y)WPP0O?DOJ5wvmujWi z2UAYn%-uW>wrel}r{ZoFO8I_doH@=j(g|BTcv9YnP|~f z+ScDL;jiOMALUYe63#)o{h(I**+&|82R&&}anc)fgYhEceh5oq?aw47SyVRJDj6W* zliKN;Vd}QvIRDPyh1pKZFG0STpGQnTjP<{3b66m2d=ZYMj`3iUrM%;)l)pj3e)Jt^ ztq!V?a$ej-H{T1mLp24seK}ZBpRXT{Td9`2Qe2s~OMl{UZ!T9~na1|zExT|OO%1IU zP+4oqf*+F?tvVz@btzYCO)o)p79TS?!rhIRxMA68PwETx#rjU>eflipII~8tav9y{ zGODLW2nRXsMl+%T{f#^^7@ZQp{4LRAwiZC}c zv{|SlJ5FDcufQ!<$F&Gc$kH<_NdY^g2Wxn-xN>lFJ!D$cqV$I@o!3!kE@G)0 z)s)t|Vcz{nsT=CvYjp^Fv5!MI_tb_{XsE-LfwGqnVqIdjiWf6ZVZR=Cdu9=j(h6X`wBn0O zBa3&GBXv~PU9YJ2=f`h!t(rni7D_ed&Y8Q_KG@f^*8D<^(L3`K zwGye^)?0c>lZOni3z=1FPvnei)uD~HcIuH^yP9Jn-0;DCAG7r=CTN(tOV=5;68rxR z!K?(<7twDeX{!&#&jNuBX``%#*U6gt|VUP!#!`cF`6x{>`2W_oKli> zel$EJo6f7jgP6|8ftoa)&&Eq;{Dq8=Pg+5Dxq*HUIAVcqp{pE1pSJv>Z9(~Y4xt~} zc0uhm(Fxmv^tUW@9C(%a;lfes%8H*e)2PRR7KWusC<*7sh2fJGu-KDRo1<{4M5Q+i z|8kr*cgKYhiFG_*amx9W7U9fMhfvmDS?WLUf|Dx`+-Qf^&S__ICLLM3NOMGF9 zRmL&eZ|b!!9pLAGL3e7VZZ<~n7~&ejhH$F}E?Ey7TLi5WD&-k1LQgDNEMLS@6fVPB zsZ*ALnN*r3{If+!ulx8a!@htxafM+E$<1Fv@GFk<7k}tQ{C`dA@9lsaOs|#(CR|he zdtP3Nk5QzikEySj&h<_!qk(}Cf{b|ZN z9Qbwnt)ggi1-^UEow6F~U+nq%X!A0p=S^9O^jT~_e^=W3y}{D+i;z2i$`a&$jofXk zqRsP=vvA5HGCs3up58m9_4#Q0)3~W;_I zND~_!#yF(+#=U~{8j^E)z?3+9^g@XCXkajd+#<}jM;;r@jl%1nARK8`-$>&gT8`q5 z=~my-9&Ya_bM0RsSNxP4V`pM-)ianqSE7wqpUNcKsg?Vr^>PU2wEeG)TJ))F1z9)H z9;FRl=t*iyXY{1Cy~COUKfAOD7i@r*yl~##(1ItHH*IS4s70u4)J*~Mb_A^}>nBFWBPLjJx>abmSEC*kyFKMdKArGDrL zZpBweg64p&c)^i_LbS*^jK>igx(xe4#NKVHoI`hzQwB5G2N$? z58*-FZRTsa%aDGp#4hY3#%n3w%WQNLjN|a@2xAu(61X0PdCchRnvl)7&1kt>d9`<} z$#x;8Hr^=DT!D)fYgxdJ^YN9;f(VvIa+!|0T`T-^!% znM|s$M|P$fUt()d)aZ-QttAhxheH@q{uUK^wpF8_s4q4<@v7V+_&D^rD*X^V>Rala z!tQq7(x%arCf1%HQ+|t!hFvxs*79d@p$9-^0U(MAPMR(h!dojZ!>L$uKYgBKa+iS%JS9ioja(mmqbk>1rGv8voD1UqH8Ce;~K z_IHwSGc48WjN>SE7T;wVQwd&(nFzXJe%lI_jJiem;c0obl?jJR`UrZrF>0u65$?9i zaAnQTwF^7Rwwoc*bUtW!w%`y-s>K+dobm$Wv)5Q@eLRLDFC`vB@g2E!Ga5gUd;gva z8_3w-V+NL6?SidUg}r;|>;kmgh5K|O%bDnN^%B(EnIcWEy;G9hEaZRDv9W%Mz0@QA zTtklkuJTNDs7e*JJ6G+{Hw&MWKYx$HZ%V$m)cEF;a4XHH&1o0j`nUO|xU6T8O}G4^ zkyPCZazFD6<8mBLoxSA;#ia4p0A(S*1YR_%^kQ7y3iN3liMy?i9%I$$12V?zTZFCF z?N&FPrc{JSc^5T1)Gl;xU1xP;=qn`MPNK=e+iFbZe0Upw5OJfU1I&wmbzAGX$K@+o z#rAF$^hCIw01HTLV;Dq`?8ZULM-E&!xUXbCX`B+2{zSM(K5SHvxa6=4Io4+Z%4@X? zBhZzJc$m01uqgY-6n6}eBKe8%&2f7E&}huy@hdl80o)nE_0ZFBJ?RLU*B?dh3y*h1 zl3h!d{4oq(B0v2R)i23m6HYjv_4BROCLDHlOvI1%G(q|U-m*IS(H^Ih{d5X?St8^k zY_!uh;V_wKQFl(n)j;oexkg5>GByjH+Q@oKIJ6R@C8*P%ttt3jEm74hq?2DQNuG;Q zcmaZ~whPlt>O0c_vP`S)E){voZQ*P2g{p~V9t#a5@UKPqdycJteToNK%KiIbC9w}` zVXNu>gDXIZ*~d@yw*QSs+jlf&i{w4N zz6c+Uw1)Fc-T$liv@b9AzZ6YPt$o1dQ_TPH>3{K_-={$>w+_Ot(dgCx$ETqG_6Y~$ z9=^(=2w!Pgww4@k{{;4t0$Vry8okD*7Oh=tI%vBm6760~-g92ZqIw>@BoXaiS94YZ z7Xa28cF7jgvh~11aBJRIzbprGmPp4(VnAh9~B0;KB6`W zS%y`e@V)*8!+}mPT_m#A1bcu)?0yvuTtHl0SJT5ABocVb5bFa;u*opp2jXF^&K-r+BW%GVnX27(`SGn@N*2s;v?K-@v$M+p4>&M1cg`(Sg; z-VqQAW91_;{e#$={onXsyr@yY4oBHeSU!`_dRnLaXFQ)8)E)~k$1rOYOpwvpux&P+ z8wKyV|Hmi8oR{F--{_i`M#F0O8^iF&7zmGB%1Xs>T6v zi;UIJm|hS&duHL(X$7$*GiMYP_fZi@40m3G9yR#wvPAsc%DS4f zMX*!$e0pn3AsraQ`BIqhj}_x)!aBphW`gb?YZ&K1ut7Ns{A;?;f>-}}JW(&i@X2iG zjV}H=8w#JN!w^GW86+Eam%;4kQ42E+oC5=+80Md@F!WJn*ggk3#W0K$|DHoHrRK>T znDo!Xabg+noWgOsC9;l$vGp!6xlY zQ?oWH!?Yu6PmKKe^M!`ZZ^IlYHOQC1tbgpo+e;w!Ii>?2cz?s`CD6lQT>{#F+>1+X z;8M^U@|Hqg{&>v33`2}Wj6n=UL?C)1bcmsdbc70_MIn43=>uG>Z;A6;L1!I&G@VCfuh?{sVu_FR&PObuP=of{T z3SY!1L=qwc5sy$KJP|nvde8vOEcW@88;8-?dIRrHpuQ%*m1DT@J>kSXqz!G_m2lnUnS|L+3B!0}ITFhd e!_AElCb@w}mf^&D2rvY1!jGT-Ikh_2BmWOVC3_11 From f8726ee6466fd9f0170cdec78365e5d754f723e3 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 4 Feb 2025 11:08:45 +1100 Subject: [PATCH 70/85] AP_HAL_ChibiOS: disable mcast bridging in bootloader --- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h index c6bb94d097d914..9e2b04e09cd87e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h @@ -65,3 +65,5 @@ #ifndef HAL_OS_POSIX_IO #define HAL_OS_POSIX_IO 0 #endif + +#define AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED 0 From 3acb03b26e800db388b196f5e57787c2347a02be Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 15 Jan 2025 10:04:47 +1100 Subject: [PATCH 71/85] autotest: add test for Rover's require-location-for-arming flag --- Tools/autotest/arducopter.py | 10 ---------- Tools/autotest/rover.py | 26 ++++++++++++++++++++++++++ Tools/autotest/vehicle_test_suite.py | 14 ++++++++++++-- 3 files changed, 38 insertions(+), 12 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 411e3ae7327761..994b47a053fa18 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -12243,16 +12243,6 @@ def GripperReleaseOnThrustLoss(self): self.context_pop() self.reboot_sitl() - def assert_home_position_not_set(self): - try: - self.poll_home_position() - except NotAchievedException: - return - - # if home.lng != 0: etc - - raise NotAchievedException("Home is set when it shouldn't be") - def REQUIRE_LOCATION_FOR_ARMING(self): '''check AP_Arming::Option::REQUIRE_LOCATION_FOR_ARMING works''' self.context_push() diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index ec6d8a5f4c7abe..3a401eb0b48090 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6947,6 +6947,31 @@ def SDPolyFence(self): self.delay_sim_time(1000) + def REQUIRE_POSITION_FOR_ARMING(self): + '''check DriveOption::REQUIRE_POSITION_FOR_ARMING works''' + self.context_push() + self.set_parameters({ + "SIM_GPS1_NUMSATS": 3, # EKF does not like < 6 + "AHRS_GPS_USE": 0, # stop DCM supplying home + }) + self.reboot_sitl() + self.change_mode('MANUAL') + self.wait_prearm_sys_status_healthy() + self.assert_home_position_not_set() + self.arm_vehicle() + self.disarm_vehicle() + + self.change_mode('GUIDED') + self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False) + + self.change_mode('MANUAL') + self.set_parameters({ + "DRIVE_OPTIONS": 1, + }) + self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False) + self.context_pop() + self.reboot_sitl() + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -7045,6 +7070,7 @@ def tests(self): self.ClearMission, self.JammingSimulation, self.BatteryInvalid, + self.REQUIRE_POSITION_FOR_ARMING, ]) return ret diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index deea94b3e2111d..daef87434f9660 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -3625,6 +3625,16 @@ def assert_bytes_equal(self, bytes1, bytes2, maxlen=None): if bytes1[i] != bytes2[i]: raise NotAchievedException("differ at offset %u" % i) + def assert_home_position_not_set(self): + try: + self.poll_home_position() + except NotAchievedException: + return + + # if home.lng != 0: etc + + raise NotAchievedException("Home is set when it shouldn't be") + def HIGH_LATENCY2(self): '''test sending of HIGH_LATENCY2''' @@ -8360,8 +8370,8 @@ def assert_prearm_failure(self, now = self.get_sim_time_cached() if now - tstart > timeout: raise NotAchievedException( - "Did not see failure-to-arm messages (statustext=%s command_ack=%s" % - (seen_statustext, seen_command_ack)) + f"Did not see failure-to-arm messages ({seen_statustext=} {expected_statustext=} {seen_command_ack=})" + ) if now - arm_last_send > 1: arm_last_send = now self.send_mavlink_run_prearms_command() From 0fb5a2105c5e0c313be36b2ce4c2ed75b7688760 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Feb 2025 14:35:48 +1100 Subject: [PATCH 72/85] AP_Arming: add option to require position for Rover before arming --- libraries/AP_Arming/AP_Arming.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index d08612bfcfd7db..6790e57593bae4 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -89,7 +89,7 @@ // whether the parameter should be shown: #ifndef AP_ARMING_NEED_LOC_PARAMETER_ENABLED // determine whether ARMING_NEED_POS is shown: -#if APM_BUILD_COPTER_OR_HELI +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover) #define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 1 #else #define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 0 @@ -98,7 +98,7 @@ // if ARMING_NEED_POS is shown, determine what its default should be: #if AP_ARMING_NEED_LOC_PARAMETER_ENABLED -#if APM_BUILD_COPTER_OR_HELI +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover) #define AP_ARMING_NEED_LOC_DEFAULT 0 #else #error "Unable to find value for AP_ARMING_NEED_LOC_DEFAULT" From 4959cee6947c58bc3e00b1cbd5f9b0d78fa311ef Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Feb 2025 14:35:48 +1100 Subject: [PATCH 73/85] Rover: add option to require position for Rover before arming --- Rover/AP_Arming_Rover.cpp | 4 +++- libraries/AP_Arming/AP_Arming.cpp | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/Rover/AP_Arming_Rover.cpp b/Rover/AP_Arming_Rover.cpp index 80534e3a93484d..8cdf9555d45f31 100644 --- a/Rover/AP_Arming_Rover.cpp +++ b/Rover/AP_Arming_Rover.cpp @@ -34,7 +34,9 @@ bool AP_Arming_Rover::rc_calibration_checks(const bool display_failure) // performs pre_arm gps related checks and returns true if passed bool AP_Arming_Rover::gps_checks(bool display_failure) { - if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) { + if (!require_location && + !rover.control_mode->requires_position() && + !rover.control_mode->requires_velocity()) { // we don't care! return true; } diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 6790e57593bae4..7c44eae1b608fd 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -191,7 +191,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @DisplayName: Require vehicle location // @Description: Require that the vehicle have an absolute position before it arms. This can help ensure that the vehicle can Return To Launch. // @User: Advanced - // @Values{Copter}: 0:Do not require location,1:Require Location + // @Values{Copter,Rover}: 0:Do not require location,1:Require Location AP_GROUPINFO("NEED_LOC", 12, AP_Arming, require_location, float(AP_ARMING_NEED_LOC_DEFAULT)), #endif // AP_ARMING_NEED_LOC_PARAMETER_ENABLED From a1cf1cf854989761d7bf8d0e0c62ce1c76d5de09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Feb 2025 14:35:48 +1100 Subject: [PATCH 74/85] Tools: add option to require position for Rover before arming --- Tools/autotest/rover.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 3a401eb0b48090..fef6519a7dd827 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6947,7 +6947,7 @@ def SDPolyFence(self): self.delay_sim_time(1000) - def REQUIRE_POSITION_FOR_ARMING(self): + def REQUIRE_LOCATION_FOR_ARMING(self): '''check DriveOption::REQUIRE_POSITION_FOR_ARMING works''' self.context_push() self.set_parameters({ @@ -6966,7 +6966,7 @@ def REQUIRE_POSITION_FOR_ARMING(self): self.change_mode('MANUAL') self.set_parameters({ - "DRIVE_OPTIONS": 1, + "ARMING_NEED_LOC": 1, }) self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False) self.context_pop() @@ -7070,7 +7070,7 @@ def tests(self): self.ClearMission, self.JammingSimulation, self.BatteryInvalid, - self.REQUIRE_POSITION_FOR_ARMING, + self.REQUIRE_LOCATION_FOR_ARMING, ]) return ret From f6922db451ed68c1e065328c11a6354d5f0f58f7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 22:16:29 +1100 Subject: [PATCH 75/85] .github: exclude QURT changes when running various workflows as we do ESP32 and ChibiOS when running SITL --- .github/workflows/cygwin_build.yml | 2 ++ .github/workflows/qurt_build.yml | 2 ++ .github/workflows/test_replay.yml | 2 ++ .github/workflows/test_sitl_blimp.yml | 2 ++ .github/workflows/test_sitl_copter.yml | 2 ++ .github/workflows/test_sitl_periph.yml | 2 ++ .github/workflows/test_sitl_plane.yml | 2 ++ .github/workflows/test_sitl_rover.yml | 2 ++ .github/workflows/test_sitl_sub.yml | 2 ++ .github/workflows/test_sitl_tracker.yml | 2 ++ .github/workflows/test_unit_tests.yml | 2 ++ 11 files changed, 22 insertions(+) diff --git a/.github/workflows/cygwin_build.yml b/.github/workflows/cygwin_build.yml index 84516aff8de578..8a09e59b669b20 100644 --- a/.github/workflows/cygwin_build.yml +++ b/.github/workflows/cygwin_build.yml @@ -9,6 +9,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -74,6 +75,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/qurt_build.yml b/.github/workflows/qurt_build.yml index 9120c9f683c2fd..dad3b3938ef725 100644 --- a/.github/workflows/qurt_build.yml +++ b/.github/workflows/qurt_build.yml @@ -9,6 +9,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -74,6 +75,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index 7799d0317aec47..b67d8f537e2289 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -13,6 +13,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -81,6 +82,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_sitl_blimp.yml b/.github/workflows/test_sitl_blimp.yml index ebd105943129db..2d4e59791c7d75 100644 --- a/.github/workflows/test_sitl_blimp.yml +++ b/.github/workflows/test_sitl_blimp.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -88,6 +89,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index 86fd5ecebada2a..227fd187a12432 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -87,6 +88,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index c65fd57a5d6448..8c8c573de9396f 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/bootloaders/**' - 'Tools/CHDK-Script/**' @@ -86,6 +87,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/bootloaders/**' - 'Tools/CHDK-Script/**' diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index 3b1e41bd4c77bf..4e1682260ced24 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -87,6 +88,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index 6adeb20060c1c8..301d3b71e867bf 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -87,6 +88,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index 427ba6c1f90b7b..3f92e07f150517 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -88,6 +89,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index 278a2d446a86be..cbf5eb8f0e49cc 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -12,6 +12,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' @@ -88,6 +89,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # remove non SITL directories - 'Tools/AP_Bootloader/**' - 'Tools/AP_Periph/**' diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index 6c04097dfd545b..791ed59ae6e078 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -43,6 +43,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # Remove change on other workflows - '.github/workflows/test_environment.yml' pull_request: @@ -88,6 +89,7 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + - 'libraries/AP_HAL_QURT/**' # Remove change on other workflows - '.github/workflows/test_environment.yml' workflow_dispatch: From 54a71cef9d0e855eef432bc0257a1571b163ac0d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 4 Feb 2025 11:22:25 +0000 Subject: [PATCH 76/85] AP_Airspeed: Calibration: remove unused DT --- libraries/AP_Airspeed/AP_Airspeed.h | 1 - libraries/AP_Airspeed/Airspeed_Calibration.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index 19488c7b0b7ea1..b73404709157a8 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -63,7 +63,6 @@ class Airspeed_Calibration { const float Q0; // process noise matrix top left and middle element const float Q1; // process noise matrix bottom right element Vector3f state; // state vector - const float DT; // time delta }; class AP_Airspeed diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 16170f9c81ea1b..941fc9890a4e75 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -25,7 +25,6 @@ Airspeed_Calibration::Airspeed_Calibration() , Q0(0.01f) , Q1(0.0000005f) , state(0, 0, 0) - , DT(1) { } From 400699fc38f393327b270baf376ea19946905ffe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Feb 2025 12:42:45 +1100 Subject: [PATCH 77/85] waf: stop clang complaining about variable-length stack arrays --- Tools/ardupilotwaf/boards.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 19c907ae1f536b..df78bc533fd112 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -287,6 +287,7 @@ def configure_env(self, cfg, env): '-Wno-gnu-variable-sized-type-not-at-end', '-Werror=implicit-fallthrough', '-cl-single-precision-constant', + '-Wno-vla-cxx-extension', ] else: env.CFLAGS += [ @@ -419,6 +420,7 @@ def configure_env(self, cfg, env): '-Wno-gnu-designator', '-Wno-mismatched-tags', + '-Wno-vla-cxx-extension', '-Wno-gnu-variable-sized-type-not-at-end', '-Werror=implicit-fallthrough', '-cl-single-precision-constant', From dd54f025d6994bd27f81c02368752e5916a1f72e Mon Sep 17 00:00:00 2001 From: Bob Long Date: Thu, 9 Jan 2025 15:44:31 +1100 Subject: [PATCH 78/85] AP_ESC_Telem: fix timeout race The timeout for non-RPM telemetry is vulnerable to a similar race as the RPM. This change makes the timeout logic consistent between the two. --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 17 ++++++++++------- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp | 6 +++--- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h | 5 ++++- 3 files changed, 17 insertions(+), 11 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 63e067525bda07..2b15c02f794fd3 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -104,13 +104,12 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con // ESC_TELEM_DATA_TIMEOUT_MS/ESC_RPM_DATA_TIMEOUT_US uint32_t AP_ESC_Telem::get_active_esc_mask() const { uint32_t ret = 0; - const uint32_t now = AP_HAL::millis(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) { // have never seen telem from this ESC continue; } - if (_telem_data[i].stale(now) && !_rpm_data[i].data_valid) { + if (_telem_data[i].stale() && !_rpm_data[i].data_valid) { continue; } ret |= (1U << i); @@ -123,13 +122,12 @@ uint8_t AP_ESC_Telem::get_max_rpm_esc() const { uint32_t ret = 0; float max_rpm = 0; - const uint32_t now = AP_HAL::millis(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) { // have never seen telem from this ESC continue; } - if (_telem_data[i].stale(now) && !_rpm_data[i].data_valid) { + if (_telem_data[i].stale() && !_rpm_data[i].data_valid) { continue; } if (_rpm_data[i].rpm > max_rpm) { @@ -405,8 +403,6 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) return; } - const uint32_t now = AP_HAL::millis(); - // loop through groups of 4 ESCs const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1); @@ -427,7 +423,7 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) for (uint8_t j=0; j<4; j++) { const uint8_t esc_id = (i * 4 + j) + esc_offset; if (esc_id < ESC_TELEM_MAX_ESCS && - (!_telem_data[esc_id].stale(now) || _rpm_data[esc_id].data_valid)) { + (!_telem_data[esc_id].stale() || _rpm_data[esc_id].data_valid)) { all_stale = false; break; } @@ -584,6 +580,7 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem telemdata.count++; telemdata.types |= data_mask; telemdata.last_update_ms = AP_HAL::millis(); + telemdata.any_data_valid = true; } // record an update to the RPM together with timestamp, this allows the notch values to be slewed @@ -807,6 +804,12 @@ void AP_ESC_Telem::update() if (AP_HAL::timeout_expired(last_updated_us, now_us, ESC_RPM_DATA_TIMEOUT_US)) { _rpm_data[i].data_valid = false; } + const uint32_t last_telem_data_ms = _telem_data[i].last_update_ms; + const uint32_t now_ms = AP_HAL::millis(); + // Invalidate telemetry data if not received for too long + if (AP_HAL::timeout_expired(last_telem_data_ms, now_ms, ESC_TELEM_DATA_TIMEOUT_MS)) { + _telem_data[i].any_data_valid = false; + } } } diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp index a63c0191c5c853..a197f6bdc1287d 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp @@ -48,9 +48,9 @@ void AP_ESC_Telem_Backend::update_telem_data(const uint8_t esc_index, const Tele /* return true if the data is stale */ -bool AP_ESC_Telem_Backend::TelemetryData::stale(uint32_t now_ms) const volatile +bool AP_ESC_Telem_Backend::TelemetryData::stale() const volatile { - return last_update_ms == 0 || now_ms - last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS; + return last_update_ms == 0 || !any_data_valid; } /* @@ -62,7 +62,7 @@ bool AP_ESC_Telem_Backend::TelemetryData::valid(const uint16_t type_mask) const // Requested type not available return false; } - return !stale(AP_HAL::millis()); + return !stale(); } #endif diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index f127c0d71ab92c..b41dc48519e879 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -30,8 +30,11 @@ class AP_ESC_Telem_Backend { uint8_t power_percentage; // Percentage of output power #endif // AP_EXTENDED_ESC_TELEM_ENABLED + // set to false if no data has been received within the timeout period + bool any_data_valid; + // return true if the data is stale - bool stale(uint32_t now_ms) const volatile; + bool stale() const volatile; // return true if the requested type of data is available and not stale bool valid(const uint16_t type_mask) const volatile; From 53701655a02b8487872214b2329c038a17e7a980 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Jan 2025 13:24:49 +1100 Subject: [PATCH 79/85] SIM_XPlane: avoid leaking memory upon json load failure ../../libraries/SITL/SIM_XPlane.cpp:209:16: warning: Potential leak of memory pointed to by 'fname' [unix.Malloc] return false; ^~~~~ --- libraries/SITL/SIM_XPlane.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index e9c147c6330438..d327832550aca1 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -206,6 +206,7 @@ bool XPlane::load_dref_map(const char *map_json) } AP_JSON::value *obj = AP_JSON::load_json(fname); if (obj == nullptr) { + free((void*)fname); return false; } From 26c61f527e7f879f1c2f518aee40b809b891f6e6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Feb 2025 21:01:59 +1100 Subject: [PATCH 80/85] SIM_XPlane: remove use-after-free issue c_str points to a member of .str(), so we have to make sure that object persists ../../libraries/SITL/SIM_XPlane.cpp:239:34: warning: object backing the pointer will be destroyed at the end of the full-expression [-Wdangling-gsl] 239 | const char *type_s = d.get("type").to_str().c_str(); --- libraries/SITL/SIM_XPlane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index d327832550aca1..637449b2809d41 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -237,7 +237,8 @@ bool XPlane::load_dref_map(const char *map_json) const char *label = i->first.c_str(); const auto &d = i->second; if (strchr(label, '/') != nullptr) { - const char *type_s = d.get("type").to_str().c_str(); + const auto str = d.get("type").to_str(); + const char *type_s = str.c_str(); if (strcmp(type_s, "angle") == 0) { add_dref(label, DRefType::ANGLE, d); } else if (strcmp(type_s, "range") == 0) { From e9e419d252c0d7970a1411e8221a07bf03ff11c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Feb 2025 15:45:39 +1100 Subject: [PATCH 81/85] autotest: add test for fetching invalid fence point --- Tools/autotest/rover.py | 43 ++++++++++++++++++++++++++++ Tools/autotest/vehicle_test_suite.py | 24 +++++++++------- 2 files changed, 57 insertions(+), 10 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index fef6519a7dd827..c4be3f75075e8b 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -2306,6 +2306,47 @@ def GCSFence(self): self.test_gcs_fence_via_mavproxy(target_system=target_system, target_component=target_component) + def GCSFenceInvalidPoint(self): + '''Test fetch non-existant fencepoint''' + target_system = 1 + target_component = 1 + + here = self.mav.location() + self.upload_fences_from_locations([ + (mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION, [ + # east + self.offset_location_ne(here, -50, 20), # bl + self.offset_location_ne(here, 50, 20), # br + self.offset_location_ne(here, 50, 40), # tr + ]), + ]) + for i in 0, 1, 2: + self.assert_fetch_mission_item_int(target_system, target_component, i, mavutil.mavlink.MAV_MISSION_TYPE_FENCE) + self.progress("Requesting invalid point") + self.mav.mav.mission_request_int_send( + target_system, + target_component, + 3, + mavutil.mavlink.MAV_MISSION_TYPE_FENCE + ) + self.context_push() + self.context_collect('MISSION_COUNT') + m = self.assert_receive_mission_ack( + mavutil.mavlink.MAV_MISSION_TYPE_FENCE, + want_type=mavutil.mavlink.MAV_MISSION_INVALID_SEQUENCE, + ) + self.delay_sim_time(0.1) + found = False + for m in self.context_collection('MISSION_COUNT'): + if m.mission_type != mavutil.mavlink.MAV_MISSION_TYPE_FENCE: + continue + if m.count != 3: + raise NotAchievedException("Unexpected count in MISSION_COUNT") + found = True + self.context_pop() + if not found: + raise NotAchievedException("Did not see correction for fencepoint count") + # explode the write_type_to_storage method # FIXME: test converting invalid fences / minimally valid fences / normal fences # FIXME: show that uploading smaller items take up less space @@ -2533,6 +2574,7 @@ def assert_receive_mission_ack(self, mission_type, if m.type != want_type: raise NotAchievedException("Expected ack type %u got %u" % (want_type, m.type)) + return m def assert_filepath_content(self, filepath, want): with open(filepath) as f: @@ -7015,6 +7057,7 @@ def tests(self): self.Offboard, self.MAVProxyParam, self.GCSFence, + self.GCSFenceInvalidPoint, self.GCSMission, self.GCSRally, self.MotorTest, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index daef87434f9660..0cb98ef1b43d15 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -9311,6 +9311,19 @@ def upload_using_mission_protocol(self, mission_type, items): (mavutil.mavlink.enums["MAV_MISSION_RESULT"][m.type].name),) self.progress("Upload of all %u items succeeded" % len(items)) + def assert_fetch_mission_item_int(self, target_system, target_component, seq, mission_type): + self.mav.mav.mission_request_int_send(target_system, + target_component, + seq, + mission_type) + m = self.assert_receive_message( + 'MISSION_ITEM_INT', + condition=f'MISSION_ITEM_INT.mission_type=={mission_type}', + ) + if m is None: + raise NotAchievedException("Did not receive MISSION_ITEM_INT") + return m + def download_using_mission_protocol(self, mission_type, verbose=False, timeout=10): '''mavlink2 required''' target_system = 1 @@ -9362,16 +9375,7 @@ def download_using_mission_protocol(self, mission_type, verbose=False, timeout=1 return items self.progress("Requesting item %u (remaining=%u)" % (next_to_request, len(remaining_to_receive))) - self.mav.mav.mission_request_int_send(target_system, - target_component, - next_to_request, - mission_type) - m = self.mav.recv_match(type='MISSION_ITEM_INT', - blocking=True, - timeout=5, - condition='MISSION_ITEM_INT.mission_type==%u' % mission_type) - if m is None: - raise NotAchievedException("Did not receive MISSION_ITEM_INT") + m = self.assert_fetch_mission_item_int(target_system, target_component, next_to_request, mission_type) if m.target_system != self.mav.source_system: raise NotAchievedException("Wrong target system (want=%u got=%u)" % (self.mav.source_system, m.target_system)) From 4161c425d14b7468cb132803f2245c6d0a9c612a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 4 Feb 2025 15:11:57 +1100 Subject: [PATCH 82/85] GCS_MAVLink: simplify MissionItemProtocol get_item interface stop passing through _link and the original msg, move use to the base class instead. starts fence and rally also using the "correct the GCS's count" code. This also corrects the error code when correcting the GCS's count to INVALID_SEQUENCE rather than just ERROR --- libraries/GCS_MAVLink/MissionItemProtocol.cpp | 23 +++++++++++-------- libraries/GCS_MAVLink/MissionItemProtocol.h | 4 +--- .../GCS_MAVLink/MissionItemProtocol_Fence.cpp | 10 +++----- .../GCS_MAVLink/MissionItemProtocol_Fence.h | 5 +--- .../GCS_MAVLink/MissionItemProtocol_Rally.cpp | 11 +++++---- .../GCS_MAVLink/MissionItemProtocol_Rally.h | 5 +--- .../MissionItemProtocol_Waypoints.cpp | 22 ++++-------------- .../MissionItemProtocol_Waypoints.h | 10 ++------ 8 files changed, 32 insertions(+), 58 deletions(-) diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index c7af789559e343..9e92377e0bb9cb 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -155,9 +155,19 @@ void MissionItemProtocol::handle_mission_request_int(GCS_MAVLINK &_link, } mavlink_mission_item_int_t ret_packet; - const MAV_MISSION_RESULT result_code = get_item(_link, msg, packet, ret_packet); - + const MAV_MISSION_RESULT result_code = get_item(packet.seq, ret_packet); if (result_code != MAV_MISSION_ACCEPTED) { + if (result_code == MAV_MISSION_INVALID_SEQUENCE) { + // try to educate the GCS on the actual size of the mission: + const mavlink_channel_t chan = _link.get_chan(); + if (HAVE_PAYLOAD_SPACE(chan, MISSION_COUNT)) { + mavlink_msg_mission_count_send(chan, + msg.sysid, + msg.compid, + item_count(), + mission_type()); + } + } // send failure message send_mission_ack(_link, msg, result_code); return; @@ -179,15 +189,8 @@ void MissionItemProtocol::handle_mission_request(GCS_MAVLINK &_link, return; } - // convert into a MISSION_REQUEST_INT and reuse its handling code - mavlink_mission_request_int_t request_int; - request_int.target_system = packet.target_system; - request_int.target_component = packet.target_component; - request_int.seq = packet.seq; - request_int.mission_type = packet.mission_type; - mavlink_mission_item_int_t item_int; - MAV_MISSION_RESULT ret = get_item(_link, msg, request_int, item_int); + MAV_MISSION_RESULT ret = get_item(packet.seq, item_int); if (ret != MAV_MISSION_ACCEPTED) { send_mission_ack(_link, msg, ret); return; diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.h b/libraries/GCS_MAVLink/MissionItemProtocol.h index 37f37fd5597165..ff8a6ae73adbf1 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.h +++ b/libraries/GCS_MAVLink/MissionItemProtocol.h @@ -102,9 +102,7 @@ class MissionItemProtocol bool mission_item_warning_sent = false; // support for GCS getting waypoints etc from us: - virtual MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, + virtual MAV_MISSION_RESULT get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) = 0; void init_send_requests(GCS_MAVLINK &_link, diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp index c50001cc12dd76..df945641c4d216 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp @@ -74,17 +74,13 @@ bool MissionItemProtocol_Fence::get_item_as_mission_item(uint16_t seq, return true; } -MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, - mavlink_mission_item_int_t &ret_packet) +MAV_MISSION_RESULT MissionItemProtocol_Fence::get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) { - const auto num_stored_items = _fence.polyfence().num_stored_items(); - if (packet.seq > num_stored_items) { + if (seq >= _fence.polyfence().num_stored_items()) { return MAV_MISSION_INVALID_SEQUENCE; } - if (!get_item_as_mission_item(packet.seq, ret_packet)) { + if (!get_item_as_mission_item(seq, ret_packet)) { return MAV_MISSION_ERROR; } diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.h b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.h index 58a984f60a821a..e724891a6622ec 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.h +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.h @@ -42,10 +42,7 @@ class MissionItemProtocol_Fence : public MissionItemProtocol { MAV_MISSION_RESULT replace_item(const mavlink_mission_item_int_t&) override WARN_IF_UNUSED; MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t&) override WARN_IF_UNUSED; - MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, - mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED; + MAV_MISSION_RESULT get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED; void free_upload_resources() override; MAV_MISSION_RESULT allocate_receive_resources(const uint16_t count) override WARN_IF_UNUSED; diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp index 0af495d7ff81a6..ad330039c33f96 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp @@ -150,12 +150,13 @@ bool MissionItemProtocol_Rally::get_item_as_mission_item(uint16_t seq, return true; } -MAV_MISSION_RESULT MissionItemProtocol_Rally::get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, - mavlink_mission_item_int_t &ret_packet) +MAV_MISSION_RESULT MissionItemProtocol_Rally::get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) { - if (!get_item_as_mission_item(packet.seq, ret_packet)) { + if (seq >= item_count()) { + return MAV_MISSION_INVALID_SEQUENCE; + } + + if (!get_item_as_mission_item(seq, ret_packet)) { return MAV_MISSION_INVALID_SEQUENCE; } return MAV_MISSION_ACCEPTED; diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.h b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.h index add6efa6ca53e5..b2aaf1ff03af24 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.h +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.h @@ -39,10 +39,7 @@ class MissionItemProtocol_Rally : public MissionItemProtocol { MAV_MISSION_RESULT replace_item(const mavlink_mission_item_int_t&) override WARN_IF_UNUSED; MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t&) override WARN_IF_UNUSED; - MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, - mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED; + MAV_MISSION_RESULT get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED; }; diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp index 7ce5787d464592..a1987c457cd120 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp @@ -64,29 +64,17 @@ MAV_MISSION_RESULT MissionItemProtocol_Waypoints::complete(const GCS_MAVLINK &_l return MAV_MISSION_ACCEPTED; } -MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, - mavlink_mission_item_int_t &ret_packet) +MAV_MISSION_RESULT MissionItemProtocol_Waypoints::get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) { - if (packet.seq != 0 && // always allow HOME to be read - packet.seq >= mission.num_commands()) { - // try to educate the GCS on the actual size of the mission: - const mavlink_channel_t chan = _link.get_chan(); - if (HAVE_PAYLOAD_SPACE(chan, MISSION_COUNT)) { - mavlink_msg_mission_count_send(chan, - msg.sysid, - msg.compid, - mission.num_commands(), - MAV_MISSION_TYPE_MISSION); - } - return MAV_MISSION_ERROR; + if (seq != 0 && // always allow HOME to be read + seq >= mission.num_commands()) { + return MAV_MISSION_INVALID_SEQUENCE; } AP_Mission::Mission_Command cmd; // retrieve mission from eeprom - if (!mission.read_cmd_from_storage(packet.seq, cmd)) { + if (!mission.read_cmd_from_storage(seq, cmd)) { return MAV_MISSION_ERROR; } diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.h b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.h index 5a7ee4e86ea36a..b5592b776447d8 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.h +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.h @@ -45,14 +45,8 @@ class MissionItemProtocol_Waypoints : public MissionItemProtocol { // item to the end of the list of stored items. MAV_MISSION_RESULT append_item(const mavlink_mission_item_int_t &) override WARN_IF_UNUSED; - // get_item() fills in ret_packet based on packet; _link is the - // link the request was received on, and msg is the undecoded - // request. Note that msg may not actually decode to a - // request_int_t! - MAV_MISSION_RESULT get_item(const GCS_MAVLINK &_link, - const mavlink_message_t &msg, - const mavlink_mission_request_int_t &packet, - mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED; + // support for GCS getting waypoints etc from us: + MAV_MISSION_RESULT get_item(uint16_t seq, mavlink_mission_item_int_t &ret_packet) override WARN_IF_UNUSED; // item_count() returns the number of stored items uint16_t item_count() const override; From db8931f6bae299608ef57026330ace737ae222b7 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Wed, 5 Feb 2025 14:42:21 -0600 Subject: [PATCH 83/85] Tools:reserve bd id for BrahamF4 --- Tools/AP_Bootloader/board_types.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index c83fe967a3f501..dadc1ed9161aca 100755 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -300,6 +300,7 @@ AP_HW_FlywooF405HD_AIOv2 1180 AP_HW_FlywooH743Pro 1181 AP_HW_CBU_StampH743_LC 1182 AP_HW_NarinH7 1183 +AP_HW_BrahmaF4 1184 AP_HW_JFB200 1200 From 8c7afb3741b8d0694a45edfbffe9b73517b45f57 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Feb 2025 23:10:09 +1100 Subject: [PATCH 84/85] waf: correct clang++ extension name seems to have changed between versions --- Tools/ardupilotwaf/boards.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index df78bc533fd112..388495c4f82837 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -287,7 +287,7 @@ def configure_env(self, cfg, env): '-Wno-gnu-variable-sized-type-not-at-end', '-Werror=implicit-fallthrough', '-cl-single-precision-constant', - '-Wno-vla-cxx-extension', + '-Wno-vla-extension', ] else: env.CFLAGS += [ @@ -420,7 +420,7 @@ def configure_env(self, cfg, env): '-Wno-gnu-designator', '-Wno-mismatched-tags', - '-Wno-vla-cxx-extension', + '-Wno-vla-extension', '-Wno-gnu-variable-sized-type-not-at-end', '-Werror=implicit-fallthrough', '-cl-single-precision-constant', From 1b0c89c8febf51f51ea9c24c6af566377e82930e Mon Sep 17 00:00:00 2001 From: Stephen Dade Date: Wed, 29 Jan 2025 19:26:11 +1100 Subject: [PATCH 85/85] AP_Scripting: Update rockblock and MAVLinkHL with additional commands and gcs timeout --- libraries/AP_Scripting/applets/RockBlock.lua | 145 ++++++++++------- libraries/AP_Scripting/applets/RockBlock.md | 5 +- libraries/AP_Scripting/examples/MAVLinkHL.lua | 150 ++++++++++++------ 3 files changed, 194 insertions(+), 106 deletions(-) diff --git a/libraries/AP_Scripting/applets/RockBlock.lua b/libraries/AP_Scripting/applets/RockBlock.lua index 2c5e175b1be1c0..9112fc0345e842 100644 --- a/libraries/AP_Scripting/applets/RockBlock.lua +++ b/libraries/AP_Scripting/applets/RockBlock.lua @@ -10,7 +10,7 @@ Usage: Use the MAVLink High Latency Control ("link hl on|off" in MAVProxy) to control whether to send or not (or use "force_hl_enable") Use the RCK_DEBUG param to view debugging statustexts at the GCS -Use the RCK_FORCEHL param to force-enable high latency mode, instead of enabling from GCS +Use the RCK_FORCEHL param to control the mode of operation: 0=Disabled, 1=Enabled, 2=Enabled on 5000ms telemetry loss Caveats: This will *only* send HIGH_LATENCY2 packets via the SBD modem. No heartbeats, @@ -24,8 +24,6 @@ The param SCR_VM_I_COUNT may need to be increased in some circumstances Written by Stephen Dade (stephen_dade@hotmail.com) ]]-- ----@diagnostic disable: cast-local-type - local PARAM_TABLE_KEY = 10 local PARAM_TABLE_PREFIX = "RCK_" @@ -39,6 +37,9 @@ end port:begin(19200) port:set_flow_control(0) +-- number of millsec that GCS telemetry has been lost for +local link_lost_for = 0 + -- bind a parameter to a variable function bind_param(name) local p = Parameter() @@ -58,7 +59,7 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 4), 'could not add p // @Param: RCK_FORCEHL // @DisplayName: Force enable High Latency mode // @Description: Automatically enables High Latency mode if not already enabled - // @Values: 0:Disabled,1:Enabled + // @Values: 0:Disabled,1:Enabled,2:Enabled on 5000ms telemetry loss // @User: Standard --]] RCK_FORCEHL = bind_add_param('FORCEHL', 1, 0) @@ -91,6 +92,13 @@ RCK_DEBUG = bind_add_param('DEBUG', 3, 0) --]] RCK_ENABLE = bind_add_param('ENABLE', 4, 1) +--[[ +Returns true if the value is NaN, false otherwise +--]] +local function isNaN (x) + return (x ~= x) + end + --[[ Lua Object for decoding and encoding MAVLink (V1 only) messages --]] @@ -102,7 +110,8 @@ local function MAVLinkProcessor() COMMAND_INT = 75, HIGH_LATENCY2 = 235, MISSION_ITEM_INT = 73, - SET_MODE = 11 + SET_MODE = 11, + MISSION_SET_CURRENT = 41 } -- private fields @@ -121,6 +130,7 @@ local function MAVLinkProcessor() _crc_extra[235] = 0xb3 _crc_extra[73] = 0x26 _crc_extra[11] = 0x59 + _crc_extra[41] = 0x1c local _messages = {} _messages[75] = { -- COMMAND_INT @@ -156,6 +166,9 @@ local function MAVLinkProcessor() _messages[11] = { -- SET_MODE { "custom_mode", " 5000 and not gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(true) + elseif link_lost_for < 5000 and gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(false) + end + end -- send HL2 packet every 30 sec, if not aleady in a mailbox check if rockblock.modem_detected and gcs:get_high_latency_status() and diff --git a/libraries/AP_Scripting/applets/RockBlock.md b/libraries/AP_Scripting/applets/RockBlock.md index edd89643da929f..ab6f0f0f395534 100644 --- a/libraries/AP_Scripting/applets/RockBlock.md +++ b/libraries/AP_Scripting/applets/RockBlock.md @@ -26,7 +26,10 @@ The script adds the following parameters: ## RCK_FORCEHL -Automatically enables High Latency mode if not already enabled +Mode of operation: +- 0 = start disabled, can be enabled via MAV_CMD_CONTROL_HIGH_LATENCY +- 1 = start enabled, can be disabled via MAV_CMD_CONTROL_HIGH_LATENCY +- 2 = enabled on loss of telemetry (GCS) link for 5 seconds ## RCK_PERIOD diff --git a/libraries/AP_Scripting/examples/MAVLinkHL.lua b/libraries/AP_Scripting/examples/MAVLinkHL.lua index 21cc968a63ec6a..7ec39a0e6ea69c 100644 --- a/libraries/AP_Scripting/examples/MAVLinkHL.lua +++ b/libraries/AP_Scripting/examples/MAVLinkHL.lua @@ -5,9 +5,13 @@ This script requires 1 serial port: A "Script" serial port to connect directly to the GCS Usage: +Use the "hl_mode" variable to control the behaviour of the script: +0 = start enabled, can be disabled via MAV_CMD_CONTROL_HIGH_LATENCY +1 = enabled on loss of telemetry link for 5 seconds (default) +2 = start disabled, can be enabled via MAV_CMD_CONTROL_HIGH_LATENCY + Use the MAVLink High Latency Control ("link hl on|off" in MAVProxy) to control whether to send or not -The script will, however, automatically enable MAVLink High Latency Control upon start Caveats: -This will send HIGH_LATENCY2 packets in place of HEARTBEAT packets @@ -19,7 +23,6 @@ Written by Stephen Dade (stephen_dade@hotmail.com) --]] ---@diagnostic disable: need-check-nil ----@diagnostic disable: cast-local-type local port = serial:find_serial(0) @@ -34,8 +37,20 @@ port:set_flow_control(0) local time_last_tx = millis():tofloat() * 0.001 +local hl_mode = 0 +local link_lost_for = 0 + -- enable high latency mode from here, instead of having to enable from GCS -gcs:enable_high_latency_connections(true) +if hl_mode == 0 then + gcs:enable_high_latency_connections(true) +end + +--[[ +Returns true if the value is NaN, false otherwise +--]] +local function isNaN (x) + return (x ~= x) + end --[[ Lua Object for decoding and encoding MAVLink (V1 only) messages @@ -48,7 +63,8 @@ local function MAVLinkProcessor() COMMAND_INT = 75, HIGH_LATENCY2 = 235, MISSION_ITEM_INT = 73, - SET_MODE = 11 + SET_MODE = 11, + MISSION_SET_CURRENT = 41 } -- private fields @@ -67,6 +83,7 @@ local function MAVLinkProcessor() _crc_extra[235] = 0xb3 _crc_extra[73] = 0x26 _crc_extra[11] = 0x59 + _crc_extra[41] = 0x1c local _messages = {} _messages[75] = { -- COMMAND_INT @@ -102,6 +119,9 @@ local function MAVLinkProcessor() _messages[11] = { -- SET_MODE { "custom_mode", " 5000 and not gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(true) + elseif link_lost_for < 5000 and gcs:get_high_latency_status() then + gcs:enable_high_latency_connections(false) + end + end + -- send HL2 packet every 5 sec if gcs:get_high_latency_status() and (millis():tofloat() * 0.001) - time_last_tx > 5 then